Skip to content

Commit

Permalink
Update for compatibility with image_pipeline 4.1.0 (#968)
Browse files Browse the repository at this point in the history
This is a PR to fix: 
- #966 

As noted in #966, as of writing image_pipeline [4.1.0 has been
released](https://github.com/ros-perception/vision_opencv/releases/tag/4.1.0),
is updated on
[index.ros.org](https://index.ros.org/p/image_geometry/github-ros-perception-vision_opencv/#rolling),
but it has not yet been migrated to
[packages.ros.org](http://packages.ros.org/ros2/ubuntu/dists/noble/main/binary-amd64/Packages).

As such `camera_calibration` will also require the source of
[image_pipeline
4.1.0](https://github.com/ros-perception/vision_opencv/releases/tag/4.1.0)
or higher to successfully build.

I tested to ensure successful build with colcon build & colcon test.

Note that colcon test has the following warning that is out of scope of
this PR:
```
=============================== warnings summary ===============================

src/camera_calibration/calibrator.py:47

  Warning: The distutils package is deprecated and slated for removal in Python 3.12. Use setuptools or check PEP 632 for potential alternatives
```
Please let me know if there are any questions, concerns, or requested
changes.
  • Loading branch information
ScottMonaghan authored May 8, 2024
1 parent 171d436 commit 794f2ee
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions camera_calibration/src/camera_calibration/calibrator.py
Original file line number Diff line number Diff line change
Expand Up @@ -1317,9 +1317,9 @@ def chessboard_size(self, lcorners, rcorners, board, msg = None):
cam = image_geometry.StereoCameraModel()
if msg == None:
msg = self.as_message()
cam.fromCameraInfo(*msg)
cam.from_camera_info(*msg)
disparities = lcorners[:,:,0] - rcorners[:,:,0]
pt3d = [cam.projectPixelTo3d((lcorners[i,0,0], lcorners[i,0,1]), disparities[i,0]) for i in range(lcorners.shape[0]) ]
pt3d = [cam.project_pixel_to_3d((lcorners[i,0,0], lcorners[i,0,1]), disparities[i,0]) for i in range(lcorners.shape[0]) ]
def l2(p0, p1):
return math.sqrt(sum([(c0 - c1) ** 2 for (c0, c1) in zip(p0, p1)]))

Expand Down

0 comments on commit 794f2ee

Please sign in to comment.