Skip to content

Commit

Permalink
Merge pull request #529 from ScottMonaghan/image_geometry-documentati…
Browse files Browse the repository at this point in the history
…on-not-generating-#528

Fix documentation generation
  • Loading branch information
ijnek authored Apr 29, 2024
2 parents f5b738d + e5a17e5 commit a34a0c2
Show file tree
Hide file tree
Showing 4 changed files with 106 additions and 36 deletions.
4 changes: 2 additions & 2 deletions image_geometry/doc/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,9 @@
# built documents.
#
# The short X.Y version.
version = '0.1'
version = '4.1'
# The full version, including alpha/beta/rc tags.
release = '0.1.0'
release = '4.1.0'

# The language for content autogenerated by Sphinx. Refer to documentation
# for a list of supported languages.
Expand Down
19 changes: 5 additions & 14 deletions image_geometry/doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,9 @@ image_geometry
image_geometry simplifies interpreting images geometrically using the
parameters from sensor_msgs/CameraInfo.

.. module:: image_geometry

.. autoclass:: image_geometry.PinholeCameraModel
:members:

.. autoclass:: image_geometry.StereoCameraModel
:members:


Indices and tables
==================

* :ref:`genindex`
* :ref:`search`
.. toctree::
:maxdepth: 2
:caption: Contents:

Python API Docs <python_api>
C++ API Docs <generated/index>
15 changes: 15 additions & 0 deletions image_geometry/doc/python_api.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
image_geometry
==============

image_geometry simplifies interpreting images geometrically using the
parameters from sensor_msgs/CameraInfo.

.. module:: image_geometry

.. autoclass:: image_geometry.PinholeCameraModel
:members:
:member-order: bysource

.. autoclass:: image_geometry.StereoCameraModel
:members:
:member-order: bysource
104 changes: 84 additions & 20 deletions image_geometry/image_geometry/cameramodels.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
import warnings
from deprecated.sphinx import deprecated

def mkmat(rows, cols, L) -> numpy.ndarray:
def _mkmat(rows, cols, L) -> numpy.ndarray:
mat = np.array(L,dtype='float64')
mat.resize(rows,cols)
return mat
Expand Down Expand Up @@ -40,15 +40,15 @@ def from_camera_info(self, msg)->None:
Set the camera parameters from the :class:`sensor_msgs.msg.CameraInfo` message.
"""
self._k = mkmat(3, 3, msg.k)
self._k = _mkmat(3, 3, msg.k)
if msg.d:
self._d = mkmat(len(msg.d), 1, msg.d)
self._d = _mkmat(len(msg.d), 1, msg.d)
else:
self._d = None
self._r = mkmat(3, 3, msg.r)
self._p = mkmat(3, 4, msg.p)
self._full_k = mkmat(3, 3, msg.k)
self._full_p = mkmat(3, 4, msg.p)
self._r = _mkmat(3, 3, msg.r)
self._p = _mkmat(3, 4, msg.p)
self._full_k = _mkmat(3, 3, msg.k)
self._full_p = _mkmat(3, 4, msg.p)
self._width = msg.width
self._height = msg.height
self._binning_x = max(1, msg.binning_x)
Expand Down Expand Up @@ -103,7 +103,7 @@ def rectify_point(self, uv_raw)->numpy.ndarray:
pixel coordinates of the rectified point.
"""

src = mkmat(1, 2, list(uv_raw))
src = _mkmat(1, 2, list(uv_raw))
src.resize((1,1,2))
dst = cv2.undistortPoints(src, self._k, self._d, R=self._r, P=self._p)
return dst[0,0]
Expand All @@ -116,9 +116,9 @@ def project_3d_to_pixel(self, point)->tuple[float,float]:
Returns the rectified pixel coordinates (u, v) of the 3D point,
using the camera :math:`P` matrix.
This is the inverse of :math:`projectPixelTo3dRay`.
This is the inverse of project_pixel_to_3d_ray().
"""
src = mkmat(4, 1, [point[0], point[1], point[2], 1.0])
src = _mkmat(4, 1, [point[0], point[1], point[2], 1.0])
dst = self._p @ src
x = dst[0,0]
y = dst[1,0]
Expand All @@ -136,7 +136,7 @@ def project_pixel_to_3d_ray(self, uv)->tuple[float,float,float]:
Returns the unit vector which passes from the camera center to through rectified pixel (u, v),
using the camera :math:`P` matrix.
This is the inverse of :math:`project_3d_to_pixel`.
This is the inverse of project_3d_to_pixel().
"""
x = (uv[0] - self.cx()) / self.fx()
y = (uv[1] - self.cy()) / self.fy()
Expand All @@ -155,7 +155,7 @@ def get_delta_u(self, delta_x, z)->float:
:rtype: float
Compute delta u, given Z and delta X in Cartesian space.
For given Z, this is the inverse of :math:`get_delta_x`.
For given Z, this is the inverse of get_delta_x().
"""
if z == 0:
return float('inf')
Expand All @@ -171,7 +171,7 @@ def get_delta_v(self, delta_y, z)->float:
:rtype: float
Compute delta v, given Z and delta Y in Cartesian space.
For given Z, this is the inverse of :math:`get_delta_y`.
For given Z, this is the inverse of get_delta_y().
"""
if z == 0:
return float('inf')
Expand All @@ -187,7 +187,7 @@ def get_delta_x(self, delta_u, z)->float:
:rtype: float
Compute delta X, given Z in cartesian space and delta u in pixels.
For given Z, this is the inverse of :math:`get_delta_u`.
For given Z, this is the inverse of get_delta_u().
"""
return z * delta_u / self.fx()

Expand All @@ -200,7 +200,7 @@ def get_delta_y(self, delta_v, z)->float:
:rtype: float
Compute delta Y, given Z in cartesian space and delta v in pixels.
For given Z, this is the inverse of :math:`get_delta_v`.
For given Z, this is the inverse of get_delta_v().
"""
return z * delta_v / self.fy()

Expand Down Expand Up @@ -339,66 +339,118 @@ def get_tf_frame(self)->str:
@property
@deprecated(version="J-turtle", reason="The binning_x property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.")
def binning_x(self):
"""
.. warning::
The binning_x property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return self._binning_x

@property
@deprecated(version="J-turtle", reason="The binning_y property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.")
def binning_y(self):
"""
.. warning::
The binning_y property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return self._binning_y

@property
@deprecated(version="J-turtle", reason="The D->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the distortion_coeffs()->numpy.ndarray method instead.")
def D(self)->numpy.matrix:
"""
.. warning::
The D property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return numpy.matrix(self._d, dtype="float64")

@property
@deprecated(version="J-turtle", reason="The full_K->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the full_intrinsic_matrix()->numpy.ndarray method instead.")
def full_K(self)->numpy.matrix:
"""
.. warning::
The full_K property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return numpy.matrix(self._full_k, dtype="float64")

@property
@deprecated(version="J-turtle", reason="The full_P->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the full_projection_matrix()->numpy.ndarray method instead.")
def full_P(self)->numpy.matrix:
"""
.. warning::
The full_P property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return numpy.matrix(self._full_p, dtype="float64")

@property
@deprecated(version="J-turtle", reason="The height property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.")
def height(self):
"""
.. warning::
The height property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return self._height

@property
@deprecated(version="J-turtle", reason="The K->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the intrinsic_matrix()->numpy.ndarray method instead.")
def K(self)->numpy.matrix:
"""
.. warning::
The K property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return numpy.matrix(self._k, dtype="float64")

@property
@deprecated(version="J-turtle", reason="The P->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the projection_matrix()->numpy.ndarray method instead.")
def P(self)->numpy.matrix:
"""
.. warning::
The P property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return numpy.matrix(self._p, dtype="float64")

@property
@deprecated(version="J-turtle", reason="The R->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the rotation_matrix()->numpy.ndarray method instead.")
def R(self)->numpy.matrix:
"""
.. warning::
The R property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return numpy.matrix(self._r)

@property
@deprecated(version="J-turtle", reason="The binning_y property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.")
def raw_roi(self):
"""
.. warning::
The raw_roi property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return self._raw_roi

@property
@deprecated(version="J-turtle", reason="The stamp property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.")
def stamp(self):
"""
.. warning::
The stamp property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return self._stamp

@property
@deprecated(version="J-turtle", reason="The tf_frame property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_tf_frame() method.")
def tf_frame(self):
"""
.. warning::
The tf_frame property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return self._tf_frame

@property
@deprecated(version="J-turtle", reason="The width property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.")
def width(self):
"""
.. warning::
The width property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return self._width

@deprecated(version="J-turtle", reason="The distortionCoeffs()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the distortion_coeffs()->numpy.ndarray method instead.")
Expand Down Expand Up @@ -757,7 +809,7 @@ def project_3d_to_pixel(self, point)->tuple[tuple[float,float],tuple[float,float
Returns the rectified pixel coordinates (u, v) of the 3D point, for each camera, as ((u_left, v_left), (u_right, v_right))
using the cameras' :math:`P` matrices.
This is the inverse of :math:`projectPixelTo3d`.
This is the inverse of project_pixel_to_3d().
"""
l = self._left.project_3d_to_pixel(point)
r = self._right.project_3d_to_pixel(point)
Expand All @@ -773,11 +825,11 @@ def project_pixel_to_3d(self, left_uv, disparity)->tuple[float,float,float]:
Returns the 3D point (x, y, z) for the given pixel position,
using the cameras' :math:`P` matrices.
This is the inverse of :math:`project_3d_to_pixel`.
This is the inverse of project_3d_to_pixel().
Note that a disparity of zero implies that the 3D point is at infinity.
"""
src = mkmat(4, 1, [left_uv[0], left_uv[1], disparity, 1.0])
src = _mkmat(4, 1, [left_uv[0], left_uv[1], disparity, 1.0])
dst = self._q @ src
x = dst[0, 0]
y = dst[1, 0]
Expand All @@ -795,7 +847,7 @@ def get_z(self, disparity)->float:
:rtype: float
Returns the depth at which a point is observed with a given disparity.
This is the inverse of :math:`getDisparity`.
This is the inverse of get_disparity().
Note that a disparity of zero implies Z is infinite.
"""
Expand All @@ -811,7 +863,7 @@ def get_disparity(self, z)->float:
:rtype: float
Returns the disparity observed for a point at depth Z.
This is the inverse of :math:`getZ`.
This is the inverse of get_z().
"""
if z == 0:
return float('inf')
Expand Down Expand Up @@ -839,16 +891,28 @@ def get_right_camera(self)->PinholeCameraModel:
@property
@deprecated(version="J-turtle", reason="The left property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_left_camera() method.")
def left(self):
"""
.. warning::
The left property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return self._left

@property
@deprecated(version="J-turtle", reason="The right property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_right_camera() method.")
def right(self):
"""
.. warning::
The right property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return self._right

@property
@deprecated(version="J-turtle", reason="The Q property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.")
def Q(self):
"""
.. warning::
The Q property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.
"""
return self._q

@deprecated(version="J-turtle", reason="The fromCameraInfo() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the from_camera_info() method instead.")
Expand Down

0 comments on commit a34a0c2

Please sign in to comment.