Skip to content

Commit

Permalink
Calibration fixes: better charuco creation
Browse files Browse the repository at this point in the history
  • Loading branch information
glvov-bdai committed Sep 4, 2024
1 parent aa44f49 commit 335e22c
Show file tree
Hide file tree
Showing 5 changed files with 70 additions and 20 deletions.
2 changes: 1 addition & 1 deletion spot_wrapper/calibration/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -236,7 +236,7 @@ If you like the core tools of this utility, and you'd like a more portable versi
use independent of Spot that doesn't depend on Spot Wrapper, you could recreate
the CLI tool with no dependency on Spot Wrapper with the following command:
```
cat calibration_util.py <(tail -n +3 automatic_camera_calibration_robot.py) <(tail -n +21 calibrate_multistereo_cameras_with_charuco_cli.py) > standalone_cli.py
cat calibration_util.py <(tail -n +3 automatic_camera_calibration_robot.py) <(tail -n +23 calibrate_multistereo_cameras_with_charuco_cli.py) > standalone_cli.py
```
The core capability above depends primarily on NumPy, OpenCV and standard Python libraries.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,13 @@
load_images_from_path,
multistereo_calibration_charuco,
save_calibration_parameters,
create_charuco_board
)

logging.basicConfig(
level=logging.INFO,
)

logger = logging.getLogger(__name__)


Expand Down Expand Up @@ -55,13 +57,11 @@ def main():
aruco_dict = cv2.aruco.getPredefinedDictionary(getattr(cv2.aruco, args.dict_size))
else:
raise ValueError(f"Invalid ArUco dictionary: {args.dict_size}")
charuco = cv2.aruco.CharucoBoard_create(
args.num_checkers_width,
args.num_checkers_height,
args.checker_dim,
args.marker_dim,
aruco_dict,
)
charuco = create_charuco_board(args.num_checkers_width,
args.num_checkers_height,
args.marker_dim,
aruco_dict)

logger.info(f"Loading images from {args.data_path}")
images = load_images_from_path(args.data_path)
calibration_helper(images=images, args=args, charuco=charuco, aruco_dict=aruco_dict)
Expand Down
14 changes: 6 additions & 8 deletions spot_wrapper/calibration/calibrate_spot_hand_camera_cli.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
from spot_wrapper.calibration.calibration_util import (
get_multiple_perspective_camera_calibration_dataset,
load_images_from_path,
create_charuco_board
)
from spot_wrapper.calibration.spot_in_hand_camera_calibration import (
SpotInHandCalibration,
Expand All @@ -33,14 +34,11 @@ def spot_main() -> None:
aruco_dict = cv2.aruco.getPredefinedDictionary(getattr(cv2.aruco, args.dict_size))
else:
raise ValueError(f"Invalid ArUco dictionary: {args.dict_size}")
charuco = cv2.aruco.CharucoBoard_create(
args.num_checkers_width,
args.num_checkers_height,
args.checker_dim,
args.marker_dim,
aruco_dict,
)

charuco = create_charuco_board(args.num_checkers_width,
args.num_checkers_height,
args.marker_dim,
aruco_dict)

if not args.from_data:
logger.warning("This script moves the robot around. !!! USE AT YOUR OWN RISK !!!")
logger.warning("HOLD Ctrl + C NOW TO CANCEL")
Expand Down
55 changes: 54 additions & 1 deletion spot_wrapper/calibration/calibration_util.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,60 @@
logger = logging.getLogger(__name__)

SPOT_DEFAULT_ARUCO_DICT = cv2.aruco.getPredefinedDictionary(cv2.aruco.DICT_4X4_50)
SPOT_DEFAULT_CHARUCO = cv2.aruco.CharucoBoard_create(9, 4, 0.115, 0.09, 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) -> 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(
"You're using an older version of OpenCV that has charuco outside of core capability (in contrib)"
"Consider upgrading to OpenCV >= 4.7.0 for including charuco capability in core.",
)

# 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,
)


return charuco

SPOT_DEFAULT_CHARUCO = create_charuco_board(num_checkers_width=9,
num_checkers_height=4,
checker_dim=.115,
marker_dim=.09,
aruco_dict=SPOT_DEFAULT_ARUCO_DICT)



def get_multiple_perspective_camera_calibration_dataset(
Expand Down
5 changes: 2 additions & 3 deletions spot_wrapper/calibration/spot_in_hand_camera_calibration.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,16 +41,15 @@
from spot_wrapper.calibration.calibration_util import (
convert_camera_t_viewpoint_to_origin_t_planning_frame,
est_camera_t_charuco_board_center,
SPOT_DEFAULT_ARUCO_DICT,
SPOT_DEFAULT_CHARUCO
)

logging.basicConfig(
level=logging.INFO,
)

logger = logging.getLogger(__name__)
SPOT_DEFAULT_ARUCO_DICT = cv2.aruco.getPredefinedDictionary(cv2.aruco.DICT_4X4_50)
SPOT_DEFAULT_CHARUCO = cv2.aruco.CharucoBoard_create(9, 4, 0.115, 0.09, SPOT_DEFAULT_ARUCO_DICT)


class SpotInHandCalibration(AutomaticCameraCalibrationRobot):
def __init__(self, ip: str, username: str, password: str):
Expand Down

0 comments on commit 335e22c

Please sign in to comment.