Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: intrinsic_evaluation_mode_visual_indicators #213

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,5 +1,51 @@
board_type: dot_board
# yamllint disable-line rule:truthy
board_type: chess_board
board_parameters:
cols: 8
rows: 6
cell_size: 0.1

calibration_parameters:
use_ransac_pre_rejection: true # yamllint disable-line rule:truthy
pre_rejection_iterations: 100
pre_rejection_min_hypotheses: 6
pre_rejection_max_rms_error: 0.35
max_calibration_samples: 80
max_fast_calibration_samples: 20
use_entropy_maximization_subsampling: true # yamllint disable-line rule:truthy
subsampling_pixel_cells: 16
subsampling_tilt_resolution: 15.0
subsampling_max_tilt_deg: 45.0
use_post_rejection: true # yamllint disable-line rule:truthy
post_rejection_max_rms_error: 0.35
plot_calibration_data_statistics: true # yamllint disable-line rule:truthy
plot_calibration_results_statistics: true # yamllint disable-line rule:truthy
viz_pixel_cells: 16
viz_tilt_resolution: 15.0
viz_max_tilt_deg: 45.0
viz_z_cells: 12
radial_distortion_coefficients: 5

calibrator_type: opencv

data_collector:
max_samples: 500
decorrelate_eval_samples: 5 # cspell:disable-line
max_allowed_tilt: 45.0
filter_by_speed: true # yamllint disable-line rule:truthy
max_allowed_pixel_speed: 10.0
max_allowed_speed: 0.1
filter_by_reprojection_error: true # yamllint disable-line rule:truthy
max_allowed_max_reprojection_error: 0.5
max_allowed_rms_reprojection_error: 0.3
filter_by_2d_redundancy: true # yamllint disable-line rule:truthy
min_normalized_2d_center_difference: 0.05
min_normalized_skew_difference: 0.05
min_normalized_2d_size_difference: 0.05
filter_by_3d_redundancy: true # yamllint disable-line rule:truthy
min_3d_center_difference: 1.0
min_tilt_difference: 15.0
heatmap_cells: 16
rotation_heatmap_angle_res: 10
point_2d_hist_bins: 20
point_3d_hist_bins: 20
Original file line number Diff line number Diff line change
Expand Up @@ -62,23 +62,55 @@ def squared_error(p, p1, p2):
p = p - p1
p2 = p2 - p1
p2 /= np.linalg.norm(p2)
return np.abs(np.power(np.linalg.norm(p), 2) - np.power(np.dot(p, p2), 2))
squared_distance = np.abs(np.power(np.linalg.norm(p), 2) - np.power(np.dot(p, p2), 2))
return squared_distance

if self._cached_linear_error_rms is not None:
return self._cached_linear_error_rms
if (
self._cached_linear_error_rows_rms is not None
and self._cached_linear_error_cols_rms is not None
):
return self._cached_linear_error_rows_rms, self._cached_linear_error_cols_rms

error = 0
error_rows = 0
pct_err_rows = 0.0

for j in range(self.rows):
p1 = self.image_points[j, 0]
p2 = self.image_points[j, -1]
points_dist = np.linalg.norm(p2 - p1)

for i in range(1, self.cols - 1):
p = self.image_points[j, i]
error += squared_error(p, p1, p2)
sq_error = squared_error(p, p1, p2)
error_rows += sq_error
pct_err_rows += np.sqrt(sq_error) / points_dist

self._cached_linear_error_rms = np.sqrt(error / (self.rows * (self.cols - 2)))
return self._cached_linear_error_rms
self._cached_linear_error_rows_rms = np.sqrt(error_rows / (self.rows * (self.cols - 2)))
pct_err_rows = pct_err_rows / (self.rows * (self.cols - 2))

error_cols = 0
pct_err_cols = 0.0

for j in range(self.cols):
p1 = self.image_points[0, j]
p2 = self.image_points[-1, j]
points_dist = np.linalg.norm(p2 - p1)

for i in range(1, self.rows - 1):
p = self.image_points[i, j]
sq_error = squared_error(p, p1, p2)
error_cols += sq_error
pct_err_cols += np.sqrt(sq_error) / points_dist

self._cached_linear_error_cols_rms = np.sqrt(error_cols / (self.cols * (self.rows - 2)))
pct_err_cols = pct_err_cols / (self.cols * (self.rows - 2))

return (
self._cached_linear_error_rows_rms,
self._cached_linear_error_cols_rms,
pct_err_rows,
pct_err_cols,
)

def get_flattened_cell_sizes(self):
if self._cached_flattened_cell_sizes is not None:
Expand All @@ -96,3 +128,27 @@ def get_flattened_cell_sizes(self):

self._cached_flattened_cell_sizes = cell_sizes.flatten()
return self._cached_flattened_cell_sizes

def get_aspect_ratio_pattern(self) -> float:
"""Get aspect ratio using the calibration pattern, which should be squared."""
tilt, pan = self.get_rotation_angles()
acceptance_angle = 10

# dont update if we the detection has big angles, calculation will not be accurate
if np.abs(tilt) > acceptance_angle or np.abs(pan) > acceptance_angle:
return 0.0
# Calculate distances between adjacent corners
aspect_ratio = 0
count = 0
for j in range(self.rows - 1):
for i in range(self.cols - 1):
p = self.image_points[j, i]
point_col = self.image_points[j + 1, i]
point_row = self.image_points[j, i + 1]
horizontal_distance = np.linalg.norm(p - point_row)
vertical_distance = np.linalg.norm(p - point_col)
aspect_ratio = aspect_ratio + (horizontal_distance / vertical_distance)
count += 1
aspect_ratio = aspect_ratio / ((self.rows - 1) * (self.cols - 1))

return aspect_ratio
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@ def __init__(
self._cached_normalized_skew = None
self._cached_normalized_size = None
self._cached_linear_error_rms = None
self._cached_linear_error_rows_rms = None
self._cached_linear_error_cols_rms = None
self._cached_flattened_cell_sizes = None
self._cached_center_2d = None

Expand Down Expand Up @@ -100,6 +102,14 @@ def get_linear_error_rms(self) -> float:
"""Return RMS error product of the projection of the lines of each row of the detection into the line produced by the first and line point of each row."""
raise NotImplementedError

def get_aspect_ratio_pattern(self) -> float:
"""Return aspect ratio obtained from the mean of the horizontal and vertical distances of the calibration pattern."""
raise NotImplementedError

def restart_linearity_heatmap(self):
"""Restart linearity heatmap."""
raise NotImplementedError

def get_center_2d(self) -> np.array:
"""Return the center of detection in the image."""
if self._cached_center_2d is not None:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@ def __init__(self, lock: threading.RLock, cfg: Dict = {}):
)
self.fix_principal_point = Parameter(bool, value=False, min_value=False, max_value=True)
self.fix_aspect_ratio = Parameter(bool, value=False, min_value=False, max_value=True)
self.use_lu_decomposition = Parameter(bool, value=False, min_value=False, max_value=True)
self.use_qr_decomposition = Parameter(bool, value=False, min_value=False, max_value=True)

self.set_parameters(**cfg)

Expand All @@ -54,6 +56,8 @@ def _calibration_impl(self, detections: List[BoardDetection]) -> CameraModel:
flags |= cv2.CALIB_FIX_K3 if self.radial_distortion_coefficients.value < 3 else 0
flags |= cv2.CALIB_FIX_K2 if self.radial_distortion_coefficients.value < 2 else 0
flags |= cv2.CALIB_FIX_K1 if self.radial_distortion_coefficients.value < 1 else 0
flags |= cv2.CALIB_USE_LU if self.use_lu_decomposition.value else 0
flags |= cv2.CALIB_USE_QR if self.use_qr_decomposition.value else 0

height = detections[0].get_image_height()
width = detections[0].get_image_width()
Expand Down
Loading