Skip to content

Commit

Permalink
replace disutils with python3-semver (#970)
Browse files Browse the repository at this point in the history
Fix for 
 - #969 
 
I added a dependency for `python3-semver` to replace version parsing
with `disutils`.

Please let me know if you have any questions, concerns, or additional
requested changes.
  • Loading branch information
ScottMonaghan authored Apr 23, 2024
1 parent 30b982a commit 171d436
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 3 deletions.
1 change: 1 addition & 0 deletions camera_calibration/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<depend>rclpy</depend>
<depend>std_srvs</depend>
<depend>sensor_msgs</depend>
<depend>python3-semver</depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
Expand Down
6 changes: 3 additions & 3 deletions camera_calibration/src/camera_calibration/calibrator.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
import sys
import tarfile
import time
from distutils.version import LooseVersion
from semver import VersionInfo
from enum import Enum

# Supported camera models
Expand Down Expand Up @@ -1145,7 +1145,7 @@ def cal_fromcorners(self, good):

if self.camera_model == CAMERA_MODEL.PINHOLE:
print("stereo pinhole calibration...")
if LooseVersion(cv2.__version__).version[0] == 2:
if VersionInfo.parse(cv2.__version__).major < 3:
cv2.stereoCalibrate(opts, lipts, ripts, self.size,
self.l.intrinsics, self.l.distortion,
self.r.intrinsics, self.r.distortion,
Expand All @@ -1164,7 +1164,7 @@ def cal_fromcorners(self, good):
flags = flags)
elif self.camera_model == CAMERA_MODEL.FISHEYE:
print("stereo fisheye calibration...")
if LooseVersion(cv2.__version__).version[0] == 2:
if VersionInfo.parse(cv2.__version__).major < 3:
print("ERROR: You need OpenCV >3 to use fisheye camera model")
sys.exit()
else:
Expand Down

0 comments on commit 171d436

Please sign in to comment.