Last active
November 27, 2024 02:19
-
-
Save glvov-bdai/d3d1c9f03d3d5ca6e61af296342498ff to your computer and use it in GitHub Desktop.
OpenCV Charuco Operations That Work Prior To And After 4.7
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
# https://github.com/bdaiinstitute/spot_wrapper/pull/138 | |
# https://github.com/bdaiinstitute/spot_wrapper/tree/main/spot_wrapper/calibration | |
# https://github.com/opencv/opencv/issues/26126 | |
import cv2 | |
import numpy as np | |
import argparse | |
import matplotlib.pyplot as plt | |
from typing import List, Dict, Optional, Union, Tuple | |
from copy import deepcopy | |
from glob import glob | |
import re | |
from math import radians | |
import os | |
import logging | |
import random | |
logging.basicConfig( | |
level=logging.INFO, | |
) | |
logger = logging.getLogger(__name__) | |
print(cv2.__version__) | |
OPENCV_VERSION = tuple(map(int, cv2.__version__.split("."))) | |
OPENCV_CHARUCO_LIBRARY_CHANGE_VERSION = (4,7,0) | |
SPOT_DEFAULT_ARUCO_DICT = cv2.aruco.getPredefinedDictionary(cv2.aruco.DICT_4X4_50) | |
ARUCO = SPOT_DEFAULT_ARUCO_DICT | |
def create_charuco_board( | |
num_checkers_width: int, | |
num_checkers_height: int, | |
checker_dim: float, | |
marker_dim: float, | |
aruco_dict: cv2.aruco_Dictionary, | |
legacy: bool = True | |
) -> cv2.aruco_CharucoBoard: | |
""" | |
Create a Charuco board using the provided parameters and Aruco dictionary. | |
Issues a deprecation warning if using the older 'CharucoBoard_create' method. | |
Args: | |
num_checkers_width (int): Number of checkers along the width of the board. | |
num_checkers_height (int): Number of checkers along the height of the board. | |
checker_dim (float): Size of the checker squares. | |
marker_dim (float): Size of the Aruco marker squares. | |
aruco_dict (cv2.aruco_Dictionary): The Aruco dictionary to use for marker generation. | |
Returns: | |
charuco (cv2.aruco_CharucoBoard): The generated Charuco board. | |
""" | |
opencv_version = tuple(map(int, cv2.__version__.split("."))) | |
if opencv_version < (4, 7, 0): | |
logger.warning( | |
( | |
"Creating Charuco Board..." | |
"You're using an older version of OpenCV requires the additional OpenCV Modules. " | |
"This will not work without the additional modules (opencv-python-contrib). " | |
"Consider upgrading to OpenCV >= 4.7.0 to enable " | |
"the use of this tool with base opencv (opencv-python) " | |
"without relying on additional modules." | |
), | |
) | |
# Create Charuco board using the older method | |
charuco = cv2.aruco.CharucoBoard_create( | |
num_checkers_width, | |
num_checkers_height, | |
checker_dim, | |
marker_dim, | |
aruco_dict, | |
) | |
else: | |
# Create Charuco board using the newer method | |
charuco = cv2.aruco_CharucoBoard( | |
(num_checkers_width, num_checkers_height), | |
checker_dim, | |
marker_dim, | |
aruco_dict, | |
) | |
charuco.setLegacyPattern(legacy) | |
return charuco | |
SPOT_DEFAULT_CHARUCO = create_charuco_board( | |
num_checkers_width=9, | |
num_checkers_height=5, | |
checker_dim=0.115, | |
marker_dim=0.09, | |
aruco_dict=SPOT_DEFAULT_ARUCO_DICT, | |
legacy=True | |
) | |
CHARUCO_BOARD = SPOT_DEFAULT_CHARUCO | |
def create_colorful_charuco_image(charuco_board, dim=(500,700)): | |
if OPENCV_VERSION < OPENCV_CHARUCO_LIBRARY_CHANGE_VERSION: | |
img = charuco_board.draw(outSize=dim) | |
else: | |
img = charuco_board.generateImage(outSize=dim) | |
img_color = cv2.cvtColor(img, cv2.COLOR_GRAY2BGR) | |
return img_color | |
def get_charuco_board_object_points(charuco_board: cv2.aruco_CharucoBoard, | |
corners_ids: List | np.ndarray): | |
if OPENCV_VERSION < OPENCV_CHARUCO_LIBRARY_CHANGE_VERSION: | |
corners = charuco_board.chessboardCorners | |
else: | |
corners = charuco_board.getChessboardCorners() | |
object_points = [] | |
for idx in corners_ids: | |
object_points.append(corners[idx]) | |
return np.array(object_points, dtype=np.float32) | |
def draw_colorful_chessboard_corners(img, charuco_corners, charuco_ids): | |
for i, corner in enumerate(charuco_corners): | |
corner = tuple(corner.ravel().astype(int)) | |
color = (((i/len(charuco_corners)) * 254, | |
(1- (i/len(charuco_corners))) * 254, | |
(1- (i/len(charuco_corners))) * 254)) | |
cv2.circle(img, corner, 3, color, -1) | |
# print(f"{charuco_ids[i][0] =} | {i = }") | |
if OPENCV_VERSION < OPENCV_CHARUCO_LIBRARY_CHANGE_VERSION: | |
cv2.putText(img, str(charuco_ids[i][0]), corner, cv2.FONT_HERSHEY_SIMPLEX, .6, color, 2) | |
else: | |
cv2.putText(img, str(charuco_ids[i]), corner, cv2.FONT_HERSHEY_SIMPLEX, .6, color, 2) | |
#cv2.putText(img, str(i), corner, cv2.FONT_HERSHEY_SIMPLEX, 0.4, color, 1) | |
return img | |
def apply_enforce_ascending_ids_from_bottom_left_corner(all_charuco_corners: List, | |
all_charuco_ids: List, | |
charuco_board: cv2.aruco_CharucoBoard, ) -> List: | |
num_checker_width, num_checker_height = charuco_board.getChessboardSize() | |
num_interior_corners = (num_checker_width -1) * (num_checker_height -1) | |
correlation_map = np.array([i for i in range(num_interior_corners)]) | |
# Adjust indexing to account for nested arrays | |
first_corner_height = all_charuco_corners[all_charuco_ids[0][0]][0][1] | |
last_corner_height = all_charuco_corners[all_charuco_ids[-1][0]][0][1] | |
row_num_a = 0 | |
row_num_b = num_checker_height - 2 | |
if (first_corner_height < last_corner_height): | |
logger.warning("Detected Charuco Configuration " | |
"where internal corners (detected checker corners) are numbered top down, " | |
"(left to right) as opposed to bottom up (left to right). " | |
"Enforcing bottom up numbering instead. " | |
"This ensures that the Z axis points out of the board " | |
"As opposed to -180 degrees about the X axis " | |
"relative to the Z out of the board") | |
else: | |
logger.warning("You have selected to enforce ascending ids from the bottom left corner " | |
"But it seems as if your ids are already in that form " | |
"Returning identity correlation map") | |
return [int(mapping) for mapping in correlation_map] | |
while row_num_a < row_num_b: | |
row_num_a_correlation_slice = slice(row_num_a * (num_checker_width - 1), | |
row_num_a * (num_checker_width - 1) + (num_checker_width - 1), | |
1) | |
row_num_b_correlation_slice = slice(row_num_b * (num_checker_width - 1), | |
(row_num_b * (num_checker_width - 1)) + (num_checker_width - 1), | |
1) | |
# Record A | |
precopy_row_a = deepcopy(correlation_map[row_num_a_correlation_slice]) | |
# Copy B onto A | |
correlation_map[row_num_a_correlation_slice] = correlation_map[row_num_b_correlation_slice] | |
# copy old A into B | |
correlation_map[row_num_b_correlation_slice] = precopy_row_a | |
row_num_a += 1 | |
row_num_b -= 1 | |
return [int(mapping) for mapping in correlation_map] | |
def detect_charuco_corners( | |
img: np.ndarray, | |
charuco_board: cv2.aruco_CharucoBoard, | |
aruco_dict: cv2.aruco_Dictionary, | |
visualize: bool = True, | |
enforce_ascending_ids_from_bottom_left_corner: Union[bool, None] = None | |
): | |
""" | |
Detect Charuco Corners and their IDs in an image for OpenCV versions before and after 4.7.0. | |
""" | |
# Convert the image to grayscale if it's not already | |
if len(img.shape) == 2: | |
gray = img | |
else: | |
gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) | |
if OPENCV_VERSION < OPENCV_CHARUCO_LIBRARY_CHANGE_VERSION: | |
# Older OpenCV version | |
corners, ids, _ = cv2.aruco.detectMarkers(gray, aruco_dict) | |
if ids is not None: | |
_, charuco_corners, charuco_ids = cv2.aruco.interpolateCornersCharuco( | |
corners, ids, gray, charuco_board, minMarkers=0 | |
) | |
if visualize: | |
# Convert image to color for annotation | |
img_color = cv2.cvtColor(gray, cv2.COLOR_GRAY2BGR) if len(img.shape) == 2 else img.copy() | |
img_markers = cv2.aruco.drawDetectedMarkers(img_color.copy(), corners, ids) | |
if charuco_corners is not None and charuco_ids is not None: | |
img_markers = draw_colorful_chessboard_corners(img_markers, charuco_corners, | |
charuco_ids) | |
plt.figure() | |
plt.imshow(cv2.cvtColor(img_markers, cv2.COLOR_BGR2RGB)) | |
plt.title('Detector Charuco Board Results') | |
plt.show() | |
return charuco_corners, charuco_ids | |
else: | |
# Newer OpenCV version with CharucoDetector | |
detector_params = cv2.aruco.CharucoParameters() | |
detector_params.minMarkers = 0 | |
detector_params.tryRefineMarkers = True | |
charucodetector = cv2.aruco.CharucoDetector(charuco_board, detector_params) | |
charucodetector.setBoard(charuco_board) | |
charuco_corners, charuco_ids, marker_corners, marker_ids = charucodetector.detectBoard(gray) | |
enforce_ids = enforce_ascending_ids_from_bottom_left_corner | |
if enforce_ids is not None and hasattr(detect_charuco_corners, | |
'enforce_ids'): | |
logger.warning("Previously, for detecting internal charuco corners, the enforce " | |
"ascending from bottom left corner id policy was set to: " | |
f"{detect_charuco_corners.enforce_ids}" | |
f"it will now be set to {enforce_ids}") | |
detect_charuco_corners.enforce_ids = enforce_ids | |
elif enforce_ids is not None and not hasattr(detect_charuco_corners, | |
'enforce_ids'): | |
logger.warning("For detecting charuco corners, the enforce " | |
"ascending from bottom left corner id policy is set to: " | |
f"{enforce_ids}. For this call, and future calls until set otherwise.") | |
detect_charuco_corners.enforce_ids = enforce_ids | |
# Create the identity correlation map... | |
num_checker_width, num_checker_height = charuco_board.getChessboardSize() | |
num_interior_corners = (num_checker_width -1) * (num_checker_height -1) | |
correlation_map = np.array([i for i in range(num_interior_corners)]) | |
if (hasattr(detect_charuco_corners, "enforce_ids") | |
and detect_charuco_corners.enforce_ids | |
and not hasattr(detect_charuco_corners, "corr_map")): # correlation map not computed | |
ideal_charuco = charuco_board.generateImage(outSize=(1000, 1000)) | |
all_charuco_corners, all_charuco_ids, _, _ = charucodetector.detectBoard(ideal_charuco) | |
detect_charuco_corners.corr_map = apply_enforce_ascending_ids_from_bottom_left_corner( | |
all_charuco_corners, all_charuco_ids, charuco_board) | |
if (hasattr(detect_charuco_corners, "enforce_ids") | |
and detect_charuco_corners.enforce_ids | |
and hasattr(detect_charuco_corners, "corr_map")): # correlation map computed | |
correlation_map = detect_charuco_corners.corr_map # grab the map | |
reworked_charuco_ids = [] | |
for charuco_id in charuco_ids: | |
reworked_charuco_ids.append(correlation_map[charuco_id[0]]) | |
if visualize: | |
img_color = cv2.cvtColor(gray, cv2.COLOR_GRAY2BGR) if len(img.shape) == 2 else img.copy() | |
img_markers = cv2.aruco.drawDetectedMarkers(img_color.copy(), marker_corners, marker_ids) | |
if charuco_corners is not None and charuco_ids is not None: | |
img_markers = draw_colorful_chessboard_corners(img_markers, charuco_corners, | |
reworked_charuco_ids) | |
plt.figure() | |
plt.imshow(cv2.cvtColor(img_markers, cv2.COLOR_BGR2RGB)) | |
plt.title('Charuco Board. Charuco Chess Corners are Gradient, Marker Corners is Blue') | |
plt.show() | |
return charuco_corners, reworked_charuco_ids | |
def visualize_object_points(): | |
if OPENCV_VERSION < OPENCV_CHARUCO_LIBRARY_CHANGE_VERSION: | |
points = CHARUCO_BOARD.objPoints | |
else: | |
points = CHARUCO_BOARD.getObjPoints() | |
plt.figure() | |
plt.gca().invert_yaxis() # Images Y axis increase download | |
for idx, point in enumerate(points): | |
colors = ['red', 'green', 'blue', 'orange'] | |
for jdx in range(4): | |
x, y = point[jdx][0], point[jdx][1] | |
plt.scatter(x, y, color=colors[idx % len(colors)]) | |
plt.text(x, y, f"i: {idx}", fontsize=9, ha='right') | |
plt.xlabel('X') | |
plt.ylabel('Y') | |
plt.title('CHARUCO_BOARD.objPoints') | |
plt.legend() | |
plt.show() | |
def visualize_chessboard_corners(): | |
if OPENCV_VERSION < OPENCV_CHARUCO_LIBRARY_CHANGE_VERSION: | |
points = CHARUCO_BOARD.chessboardCorners | |
else: | |
points = CHARUCO_BOARD.getChessboardCorners() | |
plt.figure() | |
plt.gca().invert_yaxis() | |
for idx, point in enumerate(points): | |
colors = ['red', 'green', 'blue', 'orange'] | |
x, y = point[0], point[1] | |
plt.scatter(x, y) | |
plt.text(x, y, f"{idx}", fontsize=9, ha='right') | |
plt.xlabel('X') | |
plt.ylabel('Y') | |
plt.title('CHARUCO_BOARD.chessboardCorners') | |
plt.legend() | |
plt.show() | |
def get_chessboard_pixel_coordinates(charuco_image, charuco_board, visualize=False): | |
""" | |
This method computes the pixel coordinates of the chessboard corners in a Charuco image. | |
Args: | |
- charuco_image: The grayscale Charuco image (2D NumPy array). | |
- charuco_board: The Charuco board object. | |
Returns: | |
- img_with_corners: The Charuco image with chessboard corners drawn. | |
- corner_pixel_coords: List of pixel coordinates of the chessboard corners. | |
""" | |
board_size = charuco_board.getChessboardSize() # (columns, rows) | |
square_length = charuco_board.getSquareLength() # Length of a square in meters | |
image_height, image_width = charuco_image.shape[:2] | |
# Compute the scaling factor (pixels per meter) and ensure uniform scaling for both X and Y directions | |
scaling_factor = min(image_width / (board_size[0] * square_length), | |
image_height / (board_size[1] * square_length)) | |
# Compute the offset to center the board in the image | |
x_offset = (image_width - board_size[0] * square_length * scaling_factor) / 2 | |
y_offset = (image_height - board_size[1] * square_length * scaling_factor) / 2 | |
if OPENCV_VERSION < OPENCV_CHARUCO_LIBRARY_CHANGE_VERSION: | |
points = charuco_board.chessboardCorners | |
else: | |
points = charuco_board.getChessboardCorners() | |
corner_pixel_coords = [] | |
img_with_corners = charuco_image.copy() | |
for idx, point in enumerate(points): | |
x_pixel = int(point[0] * scaling_factor + x_offset) | |
y_pixel = int(point[1] * scaling_factor + y_offset) | |
corner_pixel_coords.append((x_pixel, y_pixel)) | |
cv2.circle(img_with_corners, (x_pixel, y_pixel), 3, 255, -1) # Draw white circles | |
cv2.putText(img_with_corners, f"{idx}", (x_pixel, y_pixel), | |
cv2.FONT_HERSHEY_SIMPLEX, 0.6, 255, 2, cv2.LINE_AA) | |
if visualize: | |
plt.figure() | |
plt.imshow(img_with_corners, cmap='gray') | |
plt.title(".getChessboardCorners() or .chessboardCorners Projected to Aruco ") | |
plt.show() | |
return corner_pixel_coords | |
def get_object_pixel_coordinates(charuco_image, charuco_board, visualize=False): | |
""" | |
This method computes the pixel coordinates of the object points in the Charuco board in a Charuco image. | |
Args: | |
- charuco_image: The grayscale Charuco image (2D NumPy array). | |
- charuco_board: The Charuco board object. | |
Returns: | |
- img_with_object_points: The Charuco image with object points drawn. | |
- object_pixel_coords: List of pixel coordinates of the object points. | |
""" | |
board_size = charuco_board.getChessboardSize() # (columns, rows) | |
square_length = charuco_board.getSquareLength() # Length of a square in meters | |
image_height, image_width = charuco_image.shape[:2] | |
# Compute the scaling factor (pixels per meter) and ensure uniform scaling for both X and Y directions | |
scaling_factor = min(image_width / (board_size[0] * square_length), | |
image_height / (board_size[1] * square_length)) | |
# Compute the offset to center the board in the image | |
x_offset = (image_width - board_size[0] * square_length * scaling_factor) / 2 | |
y_offset = (image_height - board_size[1] * square_length * scaling_factor) / 2 | |
if OPENCV_VERSION < OPENCV_CHARUCO_LIBRARY_CHANGE_VERSION: | |
object_points = charuco_board.objPoints | |
else: | |
object_points = charuco_board.getObjPoints() | |
object_pixel_coords = [] | |
img_with_object_points = charuco_image.copy() | |
for idx, obj_point_set in enumerate(object_points): | |
for point in obj_point_set: | |
x_pixel = int(point[0] * scaling_factor + x_offset) | |
y_pixel = int(point[1] * scaling_factor + y_offset) | |
object_pixel_coords.append((x_pixel, y_pixel)) | |
cv2.circle(img_with_object_points, (x_pixel, y_pixel), 3, 255, -1) # Draw white circles | |
cv2.putText(img_with_object_points, f"{idx}", (x_pixel, y_pixel), | |
cv2.FONT_HERSHEY_SIMPLEX, 0.6, 255, 2, cv2.LINE_AA) | |
if visualize: | |
plt.figure() | |
plt.imshow(img_with_object_points, cmap='gray') | |
plt.title(".getObjPoints() or .objPoints Projected to Aruco ") | |
plt.show() | |
return object_pixel_coords | |
def est_camera_t_charuco_board_center( | |
img: np.ndarray, | |
charuco_board: cv2.aruco_CharucoBoard, | |
aruco_dict: cv2.aruco_Dictionary, | |
camera_matrix: np.ndarray, | |
dist_coeffs: np.ndarray, | |
visualize: bool = False | |
) -> Tuple[np.ndarray, np.ndarray]: | |
""" | |
Localizes the 6D pose of the checkerboard center using Charuco corners with OpenCV's solvePnP. | |
The board pose's translation should be at the center of the board, with the orientation in OpenCV format, | |
where the +Z points out of the board with the other axes being parallel to the sides of the board. | |
Args: | |
img (np.ndarray): The input image containing the checkerboard. | |
charuco_board (cv2.aruco_CharucoBoard): The Charuco board configuration. | |
aruco_dict (cv2.aruco_Dictionary): The Aruco dictionary used to detect markers. | |
camera_matrix (np.ndarray): The camera matrix from calibration. | |
dist_coeffs (np.ndarray): The distortion coefficients from calibration. | |
Returns: | |
Optional[Tuple[np.ndarray, np.ndarray]]: The rotation vector and translation vector | |
representing the 6D pose of the checkerboard center if found, else None. | |
""" | |
charuco_corners, charuco_ids = detect_charuco_corners(img, charuco_board, aruco_dict, visualize=False) | |
if charuco_corners is not None and charuco_ids is not None: | |
object_points = get_charuco_board_object_points(charuco_board, charuco_ids) | |
image_points = charuco_corners | |
# Use solvePnP to estimate the pose of the Charuco board | |
success, rvec, tvec = cv2.solvePnP( | |
object_points, np.array(image_points), camera_matrix, dist_coeffs | |
) | |
if success: | |
# Convert to the camera frame: Adjust the translation vector to be relative to the center of the board | |
x_trans = (charuco_board.getSquareLength() * charuco_board.getChessboardSize()[0]) / 2.0 | |
y_trans = (charuco_board.getSquareLength() * charuco_board.getChessboardSize()[1]) / 2.0 | |
center_trans = np.array([x_trans, y_trans, 0.0]).reshape((3, 1)) | |
rmat, _ = cv2.Rodrigues(rvec) | |
tvec = tvec + rmat.dot(center_trans) | |
tvec_to_camera = -rmat.T @ tvec | |
if visualize: | |
img_with_axis = img.copy() | |
cv2.drawFrameAxes(img_with_axis, camera_matrix, dist_coeffs, rvec, tvec, 0.115) | |
plt.figure() | |
plt.imshow(cv2.cvtColor(img_with_axis, cv2.COLOR_BGR2RGB)) | |
plt.show() | |
return np.array(rmat), np.array(tvec_to_camera).ravel() | |
else: | |
raise ValueError( | |
"Pose estimation failed. You likely primed the robot too close to the board." | |
) | |
else: | |
raise ValueError( | |
"Couldn't detect any Charuco boards in the image, " | |
"localization failed. Ensure the board is visible from the" | |
" primed pose." | |
) | |
def charuco_pose_sanity_check(img, charuco_board, aruco_dict): | |
""" | |
This method: | |
1. Defines the camera matrix as identity. | |
2. Uses zero distortion coefficients. | |
3. Estimates the Charuco board pose using `est_camera_t_charuco_board_center`. | |
4. Transforms the pose into the camera frame. | |
5. Visualizes the pose with 3D axes on the image. | |
Args: | |
img (np.ndarray): The input image containing the Charuco board. | |
charuco_board (cv2.aruco_CharucoBoard): The Charuco board configuration. | |
aruco_dict (cv2.aruco_Dictionary): The Aruco dictionary used to detect markers. | |
Returns: | |
img_with_axes (np.ndarray): The image with the pose axes drawn. | |
""" | |
def is_z_axis_out_of_board(tvec): | |
"""Determine if the Z-axis points out of the Charuco board (towards the camera).""" | |
return tvec[2] > 0 # If Z is positive, it points out of the board | |
def transform_pose_to_camera_frame(rmat, tvec): | |
"""Transforms the pose to the camera frame by applying the inverse of the rotation.""" | |
return rmat.T, -np.dot(rmat.T, tvec) | |
def visualize_pose_with_axis(img, rmat, tvec, camera_matrix, dist_coeffs, axis_length=0.115): | |
"""Draws the 3D pose axes on the image and displays if the Z-axis is out or into the board.""" | |
axis = np.float32([ | |
[axis_length, 0, 0], [0, axis_length, 0], [0, 0, axis_length], [0, 0, 0] | |
]).reshape(-1, 3) | |
rmat_camera, tvec_camera = transform_pose_to_camera_frame(rmat, tvec) | |
imgpts, _ = cv2.projectPoints(axis, rmat_camera, tvec_camera, camera_matrix, dist_coeffs) | |
z_out_of_board = is_z_axis_out_of_board(tvec) | |
img_with_axes = img.copy() | |
origin = tuple(imgpts[3].ravel().astype(int)) | |
img_with_axes = cv2.line(img_with_axes, origin, tuple(imgpts[0].ravel().astype(int)), (0, 0, 255), 3) # X | |
img_with_axes = cv2.line(img_with_axes, origin, tuple(imgpts[1].ravel().astype(int)), (0, 255, 0), 3) # Y | |
img_with_axes = cv2.line(img_with_axes, origin, tuple(imgpts[2].ravel().astype(int)), (255, 0, 0), 3) # Z | |
plt.figure() | |
plt.imshow(cv2.cvtColor(img_with_axes, cv2.COLOR_BGR2RGB)) | |
plt.title(f'Charuco Board with Pose Axes ({"Z-axis out of board" if z_out_of_board else "Z-axis into board"})') | |
plt.show() | |
return img_with_axes | |
# Camera matrix as identity and zero distortion coefficients | |
camera_matrix = np.eye(3, dtype=np.float32) | |
dist_coeffs = np.zeros(5, dtype=np.float32) | |
# Estimate pose using the existing est_camera_t_charuco_board_center | |
rmat, tvec = est_camera_t_charuco_board_center( | |
img, charuco_board, aruco_dict, camera_matrix, dist_coeffs, visualize=False | |
) | |
# Visualize the pose with 3D axes | |
return visualize_pose_with_axis(img, rmat, tvec, camera_matrix, dist_coeffs) | |
def parse_args(): | |
""" | |
Parse command-line arguments to control board dimensions, legacy flag, and ID enforcement. | |
""" | |
parser = argparse.ArgumentParser(description="Charuco Board Pose Estimation Script") | |
parser.add_argument('--board_width', type=int, default=9, help='Number of checkers along the width of the board.') | |
parser.add_argument('--board_height', type=int, default=5, help='Number of checkers along the height of the board.') | |
parser.add_argument('--checker_dim', type=float, default=0.115, help='Size of the checker squares in meters.') | |
parser.add_argument('--marker_dim', type=float, default=0.09, help='Size of the Aruco marker squares in meters.') | |
parser.add_argument('--legacy', action='store_true', default=False, help='Use legacy mode for Charuco board creation.') | |
parser.add_argument('--enforce_ascending_ids', action='store_true', default=False, help='Enforce ascending IDs from bottom left corner.') | |
return parser.parse_args() | |
def main(): | |
args = parse_args() | |
# Create Charuco board based on the command-line arguments | |
charuco_board = create_charuco_board( | |
num_checkers_width=args.board_width, | |
num_checkers_height=args.board_height, | |
checker_dim=args.checker_dim, | |
marker_dim=args.marker_dim, | |
aruco_dict=SPOT_DEFAULT_ARUCO_DICT, | |
legacy=args.legacy | |
) | |
img_color = create_colorful_charuco_image(charuco_board) | |
# Detect Charuco corners with ID enforcement if specified | |
detect_charuco_corners( | |
img_color, | |
charuco_board, | |
ARUCO, | |
visualize=True, | |
enforce_ascending_ids_from_bottom_left_corner=args.enforce_ascending_ids | |
) | |
# Visualize object points and chessboard corners | |
visualize_object_points() | |
visualize_chessboard_corners() | |
# Get pixel coordinates for chessboard and object points | |
chess_corners_pixel_coords = get_chessboard_pixel_coordinates(img_color, charuco_board, visualize=True) | |
object_pixel_coords = get_object_pixel_coordinates(img_color, charuco_board, visualize=True) | |
# Perform pose sanity check | |
img_with_pose = charuco_pose_sanity_check(img_color, charuco_board, ARUCO) | |
if __name__ == "__main__": | |
main() |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment