diff --git a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_calibrator.py b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_calibrator.py index 57edeec6..874fdc79 100644 --- a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_calibrator.py +++ b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_calibrator.py @@ -233,7 +233,7 @@ def on_evaluation_sample_changed(index): self.process_db_data(img) def on_rectify_type_change(index): - self.calibrated_camera_model._cached_undistorted_model = None + self.calibrated_camera_model.restart_camera_cached_model() self.pause_button.clicked.connect(pause_callback) self.image_view_type_combobox.currentIndexChanged.connect(on_image_view_type_change) diff --git a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_models/camera_model.py b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_models/camera_model.py index 861c8edc..6c58233c 100644 --- a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_models/camera_model.py +++ b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_models/camera_model.py @@ -355,6 +355,10 @@ def _calibrate_impl( def _update_config_impl(self, **kwargs): """Abstract method to update the camera model configuration.""" raise NotImplementedError + + def restart_camera_cached_model(self): + """Restarts the current cached camera model""" + self._cached_undistorted_model = None class CameraModelWithBoardDistortion(CameraModel):