| |
- R_from_quat(...)
- Convert a rotation defined as a unit quaternion rotation to a rotation matrix
SYNOPSIS
s = np.sin(rotation_magnitude/2.)
c = np.cos(rotation_magnitude/2.)
quat = nps.glue( c, s*rotation_axis, axis = -1)
print(quat.shape)
===>
(4,)
R = mrcal.R_from_quat(quat)
print(R.shape)
===>
(3,3)
This is mostly for compatibility with some old stuff. mrcal doesn't use
quaternions anywhere. Test this thoroughly before using.
This function supports broadcasting fully.
ARGUMENTS
- quat: array of shape (4,). The unit quaternion that defines the rotation. The
values in the array are (u,i,j,k)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If 'out'
is given, we return the 'out' that was passed in. This is the standard
behavior provided by numpysane_pywrap.
RETURNED VALUE
We return an array of rotation matrices. Each broadcasted slice has shape (3,3)
- R_from_r(r, *, get_gradients=False, out=None)
- Compute a rotation matrix from a Rodrigues vector
SYNOPSIS
r = rotation_axis * rotation_magnitude
R = mrcal.R_from_r(r)
Given a rotation specified as a Rodrigues vector (a unit rotation axis scaled by
the rotation magnitude, in radians.), converts it to a rotation matrix.
By default this function returns the rotation matrices only. If we also want
gradients, pass get_gradients=True. Logic:
if not get_gradients: return R
else: return (R, dR/dr)
This function supports broadcasting fully.
ARGUMENTS
- r: array of shape (3,). The Rodrigues vector that defines the rotation. This is
a unit rotation axis scaled by the rotation magnitude, in radians
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of rotation matrices. Otherwise we return a tuple of arrays of rotation
matrices and their gradients.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return an array of rotation matrices. Each broadcasted
slice has shape (3,3)
If get_gradients: we return a tuple of arrays containing the rotation matrices
and the gradient (R, dR/dr):
1. The rotation matrix. Each broadcasted slice has shape (3,3). This is a valid
rotation: matmult(R,transpose(R)) = I, det(R) = 1
2. The gradient dR/dr. Each broadcasted slice has shape (3,3,3). The first two
dimensions select the element of R, and the last dimension selects the
element of r
- Rt_from_qt(qt, *, out=None)
- Compute an Rt transformation from a qt transformation
SYNOPSIS
qt = nps.glue(q,t, axis=-1)
print(qt.shape)
===>
(7,)
Rt = mrcal.Rt_from_qt(qt)
print(Rt.shape)
===>
(4,3)
translation = Rt[3,:]
rotation_matrix = Rt[:3,:]
Converts a qt transformation to an Rt transformation. Both specify a rotation
and translation. An Rt transformation is a (4,3) array formed by nps.glue(R,t,
axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector.
A qt transformation is a (7,) array formed by nps.glue(q,t, axis=-1) where q is
a (4,) unit quaternion and t is a (3,) translation vector.
Applied to a point x the transformed result is rotate(x)+t. Given a matrix R,
the rotation is defined by a matrix multiplication. x and t are stored as a row
vector (that's how numpy stores 1-dimensional arrays), but the multiplication
works as if x was a column vector (to match linear algebra conventions). See the
docs for mrcal._transform_point_Rt() for more detail.
This function supports broadcasting fully.
Note: mrcal does not use unit quaternions anywhere to represent rotations. This
function is provided for convenience, but isn't thoroughly tested.
ARGUMENTS
- qt: array of shape (7,). This vector defines the input transformation. qt[:4]
is a rotation defined as a unit quaternion; qt[4:] is a translation.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg.
RETURNED VALUE
We return the Rt transformation. Each broadcasted slice has shape (4,3).
Rt[:3,:] is a rotation matrix; Rt[3,:] is a translation. The matrix R is a valid
rotation: matmult(R,transpose(R)) = I and det(R) = 1
- Rt_from_rt(rt, *, get_gradients=False, out=None)
- Compute an Rt transformation from a rt transformation
SYNOPSIS
r = rotation_axis * rotation_magnitude
rt = nps.glue(r,t, axis=-1)
print(rt.shape)
===>
(6,)
Rt = mrcal.Rt_from_rt(rt)
print(Rt.shape)
===>
(4,3)
translation = Rt[3,:]
rotation_matrix = Rt[:3,:]
Converts an rt transformation to an Rt transformation. Both specify a rotation
and translation. An Rt transformation is a (4,3) array formed by nps.glue(R,t,
axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector.
An rt transformation is a (6,) array formed by nps.glue(r,t, axis=-1) where r is
a (3,) Rodrigues vector and t is a (3,) translation vector.
Applied to a point x the transformed result is rotate(x)+t. Given a matrix R,
the rotation is defined by a matrix multiplication. x and t are stored as a row
vector (that's how numpy stores 1-dimensional arrays), but the multiplication
works as if x was a column vector (to match linear algebra conventions). See the
docs for mrcal._transform_point_Rt() for more detail.
By default this function returns the Rt transformations only. If we also want
gradients, pass get_gradients=True. Logic:
if not get_gradients: return Rt
else: return (Rt, dR/dr)
Note that the translation gradient isn't returned: it is always the identity
This function supports broadcasting fully.
ARGUMENTS
- rt: array of shape (6,). This vector defines the input transformation. rt[:3]
is a rotation defined as a Rodrigues vector; rt[3:] is a translation.
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of Rt transformations. Otherwise we return a tuple of arrays of Rt
transformations and their gradients.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return the Rt transformation. Each broadcasted slice
has shape (4,3). Rt[:3,:] is a rotation matrix; Rt[3,:] is a translation. The
matrix R is a valid rotation: matmult(R,transpose(R)) = I and det(R) = 1
If get_gradients: we return a tuple of arrays containing the Rt transformation
and the gradient (Rt, dR/dr):
1. The Rt transformation. Each broadcasted slice has shape (4,3,)
2. The gradient dR/dr. Each broadcasted slice has shape (3,3,3). The first two
dimensions select the element of R, and the last dimension selects the
element of r
- align_procrustes_points_Rt01(p0, p1, weights=None)
- Compute a rigid transformation to align two point clouds
SYNOPSIS
print(points0.shape)
===>
(100,3)
print(points1.shape)
===>
(100,3)
Rt01 = mrcal.align_procrustes_points_Rt01(points0, points1)
print( np.sum(nps.norm2(mrcal.transform_point_Rt(Rt01, points1) -
points0)) )
===>
[The fit error from applying the optimal transformation. If the two point
clouds match up, this will be small]
Given two sets of 3D points in numpy arrays of shape (N,3), we find the optimal
rotation, translation to align these sets of points. This is done with a
well-known direct method. See:
- https://en.wikipedia.org/wiki/Orthogonal_Procrustes_problem
- https://en.wikipedia.org/wiki/Kabsch_algorithm
We return a transformation that minimizes the sum 2-norm of the misalignment:
cost = sum( norm2( w[i] (a[i] - transform(b[i])) ))
We return an Rt transformation to map points in set 1 to points in set 0.
A similar computation can be performed to instead align a set of UNIT VECTORS to
compute an optimal rotation matrix R by calling align_procrustes_vectors_R01().
ARGUMENTS
- p0: an array of shape (..., N, 3). Each row is a point in the coordinate
system we're transforming TO
- p1: an array of shape (..., N, 3). Each row is a point in the coordinate
system we're transforming FROM
- weights: optional array of shape (..., N). Specifies the relative weight of
each point. If omitted, all the given points are weighted equally
RETURNED VALUES
The Rt transformation in an array of shape (4,3). We return the optimal
transformation to align the given point clouds. The transformation maps points
TO coord system 0 FROM coord system 1.
- align_procrustes_vectors_R01(v0, v1, weights=None)
- Compute a rotation to align two sets of direction vectors
SYNOPSIS
print(vectors0.shape)
===>
(100,3)
print(vectors1.shape)
===>
(100,3)
R01 = mrcal.align_procrustes_vectors_R01(vectors0, vectors1)
print( np.mean(1. - nps.inner(mrcal.rotate_point_R(R01, vectors1),
vectors0)) )
===>
[The fit error from applying the optimal rotation. If the two sets of
vectors match up, this will be small]
Given two sets of normalized direction vectors in 3D (stored in numpy arrays of
shape (N,3)), we find the optimal rotation to align them. This is done with a
well-known direct method. See:
- https://en.wikipedia.org/wiki/Orthogonal_Procrustes_problem
- https://en.wikipedia.org/wiki/Kabsch_algorithm
We return a rotation that minimizes the weighted sum of the cosine of the
misalignment:
cost = -sum( w[i] inner(a[i], rotate(b[i])) )
We return a rotation to map vectors in set 1 to vectors in set 0.
A similar computation can be performed to instead align a set of POINTS to
compute an optimal transformation Rt by calling align_procrustes_points_Rt01().
ARGUMENTS
- v0: an array of shape (..., N, 3). Each row is a vector in the coordinate
system we're transforming TO. These are assumed normalized.
- v1: an array of shape (..., N, 3). Each row is a vector in the coordinate
system we're transforming FROM. These are assumed normalized.
- weights: optional array of shape (..., N). Specifies the relative weight of
each vector. If omitted, everything is weighted equally
RETURNED VALUES
The rotation matrix in an array of shape (3,3). We return the optimal rotation
to align the given vector sets. The rotation maps vectors TO coord system 0 FROM
coord system 1.
- annotate_image__valid_intrinsics_region(image, model, *, color=(0, 255, 0))
- Annotate an image with a model's valid-intrinsics region
SYNOPSIS
model = mrcal.cameramodel('cam0.cameramodel')
image = mrcal.load_image('image.jpg')
mrcal.annotate_image__valid_intrinsics_region(image, model)
mrcal.save_image('image-annotated.jpg', image)
This function reads a valid-intrinsics region from a given camera model, and
draws it on top of a given image. This is useful to see what parts of a captured
image have reliable intrinsics.
This function modifies the input image.
If the given model has no valid-intrinsics region defined, an exception is
thrown. If the valid-intrinsics region is empty, a solid circle is drawn at the
center.
If we want an interactive plot instead of an annotated image, call
mrcal.show_valid_intrinsics_region() instead.
ARGUMENTS
- model: the mrcal.cameramodel object that contains the valid-intrinsics region
contour
- image: the numpy array containing the image we're annotating. This is both an
input and an output
- color: optional tuple of length 3 indicating the BGR color of the annotation.
Green by default
RETURNED VALUES
None. The input image array is modified
- apply_color_map(array, a_min=None, a_max=None)
- Color-code an array
SYNOPSIS
image = produce_data()
print( image.shape )
===>
(480, 640)
image_colorcoded = mrcal.apply_color_map(image)
print( image_colorcoded.shape )
===>
(480, 640, 3)
print( image_colorcoded.dtype )
===>
dtype('uint8')
mrcal.save_image('data.png', image_colorcoded)
This is very similar to cv2.applyColorMap() but more flexible in several
important ways. Differences:
- Supports arrays of any shape. Most of the time the input is 2-dimensional
images, but this isn't required
- Supports any input data type, NOT limited to 8-bit images like
cv2.applyColorMap()
- Does not support MATLAB color maps. At this time only one color map is
supported (the default Gnuplot color map). Other gnuplot color maps will be
supported in the future.
The color map is applied to each value in the input, each one producing an BGR
row of shape (3,). So output.shape is input.shape + (3,).
The output has dtype=numpy.uint8, so these arrays can be output as images, and
visualized using any image-viewing tools.
At this time only one color map is supported: the default color map used by
gnuplot. Support for others will be added in the future.
ARGUMENTS
- array: input numpy array
- a_min: optional value indicating the lower bound of the values we color map.
All input values outside of the range [a_min,a_max] are clipped. If omitted, I
use array.min()
- a_max: optional value indicating the upper bound of the values we color map.
All input values outside of the range [a_min,a_max] are clipped. If omitted, I
use array.max()
RETURNED VALUE
The color-mapped output array of shape array.shape + (3,) and containing 8-bit
unsigned integers. The last row is the BGR color-mapped values.
- apply_homography(...)
- Apply a homogeneous-coordinate homography to a set of 2D points
SYNOPSIS
print( H.shape )
===> (3,3)
print( q0.shape )
===> (100, 2)
q1 = mrcal.apply_homography(H10, q0)
print( q1.shape )
===> (100, 2)
A homography maps from pixel coordinates observed in one camera to pixel
coordinates in another. For points represented in homogeneous coordinates ((k*x,
k*y, k) to represent a pixel (x,y) for any k) a homography is a linear map H.
Since homogeneous coordinates are unique only up-to-scale, the homography matrix
H is also unique up to scale.
If two pinhole cameras are observing a planar surface, there exists a homography
that relates observations of the plane in the two cameras.
This function supports broadcasting fully.
ARGUMENTS
- H: an array of shape (..., 3,3). This is the homography matrix. This is unique
up-to-scale, so a homography H is functionally equivalent to k*H for any
non-zero scalar k
- q: an array of shape (..., 2). The pixel coordinates we are mapping
RETURNED VALUE
An array of shape (..., 2) containing the pixels q after the homography was
applied
- close_contour(c)
- Close a polyline, if it isn't already closed
SYNOPSIS
print( a.shape )
===>
(5, 2)
print( a[0] )
===>
[844 204]
print( a[-1] )
===>
[886 198]
b = mrcal.close_contour(a)
print( b.shape )
===>
(6, 2)
print( b[0] )
===>
[844 204]
print( b[-2:] )
===>
[[886 198]
[844 204]]
This function works with polylines represented as arrays of shape (N,2). The
polygon represented by such a polyline is "closed" if its first and last points
sit at the same location. This function ingests a polyline, and returns the
corresponding, closed polygon. If the first and last points of the input match,
the input is returned. Otherwise, the first point is appended to the end, and
this extended polyline is returned.
None is accepted as an empty polygon: we return None.
ARGUMENTS
- c: an array of shape (N,2) representing the polyline to be closed. None and
arrays of shape (0,2) are accepted as special cases ("unknown" and "empty"
regions, respectively)
RETURNED VALUE
An array of shape (N,2) representing the closed polygon. The input is returned
if the input was None or has shape (0,2)
- compose_Rt(*Rt, out=None)
- Compose Rt transformations
SYNOPSIS
Rt10 = nps.glue(rotation_matrix10,translation10, axis=-2)
Rt21 = nps.glue(rotation_matrix21,translation21, axis=-2)
Rt32 = nps.glue(rotation_matrix32,translation32, axis=-2)
print(Rt10.shape)
===>
(4,3)
Rt30 = mrcal.compose_Rt( Rt32, Rt21, Rt10 )
print(x0.shape)
===>
(3,)
print( nps.norm2( mrcal.transform_point_Rt(Rt30, x0) -
mrcal.transform_point_Rt(Rt32,
mrcal.transform_point_Rt(Rt21,
mrcal.transform_point_Rt(Rt10, x0)))))
===>
0
Given 2 or more Rt transformations, returns their composition. An Rt
transformation is a (4,3) array formed by nps.glue(R,t, axis=-2) where R is a
(3,3) rotation matrix and t is a (3,) translation vector. This transformation is
defined by a matrix multiplication and an addition. x and t are stored as a row
vector (that's how numpy stores 1-dimensional arrays), but the multiplication
works as if x was a column vector (to match linear algebra conventions):
transform_point_Rt(Rt, x) = transpose( matmult(Rt[:3,:], transpose(x)) +
transpose(Rt[3,:]) ) =
= matmult(x, transpose(Rt[:3,:])) +
Rt[3,:]
This function supports broadcasting fully, so we can compose lots of
transformations at the same time.
In-place operation is supported; the output array may be the same as either of
the input arrays to overwrite the input.
ARGUMENTS
- *Rt: a list of transformations to compose. Usually we'll be composing two
transformations, but any number could be given here. Each broadcasted slice
has shape (4,3).
- out: optional argument specifying the destination. By default, a new numpy
array is created and returned. To write the results into an existing (and
possibly non-contiguous) array, specify it with the 'out' kwarg. If 'out' is
given, we return the 'out' that was passed in. This is the standard behavior
provided by numpysane_pywrap.
RETURNED VALUE
An array of composed Rt transformations. Each broadcasted slice has shape (4,3)
- compose_r(*r, get_gradients=False, out=None)
- Compose angle-axis rotations
SYNOPSIS
r10 = rotation_axis10 * rotation_magnitude10
r21 = rotation_axis21 * rotation_magnitude21
r32 = rotation_axis32 * rotation_magnitude32
print(r10.shape)
===>
(3,)
r30 = mrcal.compose_r( r32, r21, r10 )
print(x0.shape)
===>
(3,)
print( nps.norm2( mrcal.rotate_point_r(r30, x0) -
mrcal.rotate_point_r(r32,
mrcal.rotate_point_r(r21,
mrcal.rotate_point_r(r10, x0)))))
===>
0
print( [arr.shape for arr in mrcal.compose_r(r21,r10,
get_gradients = True)] )
===>
[(3,), (3,3), (3,3)]
Given 2 or more axis-angle rotations, returns their composition. By default this
function returns the composed rotation only. If we also want gradients, pass
get_gradients=True. This is supported ONLY if we have EXACTLY 2 rotations to
compose. Logic:
if not get_gradients: return r=compose(r0,r1)
else: return (r=compose(r0,r1), dr/dr0, dr/dr1)
This function supports broadcasting fully, so we can compose lots of
rotations at the same time.
In-place operation is supported; the output array may be the same as either of
the input arrays to overwrite the input.
ARGUMENTS
- *r: a list of rotations to compose. Usually we'll be composing two rotations,
but any number could be given here. Each broadcasted slice has shape (3,)
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of composed rotations. Otherwise we return a tuple of arrays of composed
rotations and their gradients. Gradient reporting is only supported when
exactly two rotations are given
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return an array of composed rotations. Each broadcasted
slice has shape (3,)
If get_gradients: we return a tuple of arrays containing the composed rotations
and the gradients (r=compose(r0,r1), dr/dr0, dr/dr1):
1. The composed rotation. Each broadcasted slice has shape (3,)
2. The gradient dr/dr0. Each broadcasted slice has shape (3,3). The first
dimension selects the element of r, and the last dimension selects the
element of r0
3. The gradient dr/dr1. Each broadcasted slice has shape (3,3). The first
dimension selects the element of r, and the last dimension selects the
element of r1
- compose_r_tinyr0_gradientr0(...)
- Special-case rotation composition for the uncertainty computation
SYNOPSIS
r1 = rotation_axis1 * rotation_magnitude1
dr01_dr0 = compose_r_tinyr0_gradientr0(r1)
### Another way to get the same thing (but possibly less efficiently)
_,dr01_dr0,_ = compose_r(np.zeros((3,),),
r1,
get_gradients=True)
This is a special-case subset of compose_r(). It is the same, except:
- r0 is assumed to be 0, so we don't ingest it, and we don't report the
composition result
- we ONLY report the dr01/dr0 gradient
This special-case function is a part of the projection uncertainty computation,
so it exists by itself. See the documentation for compose_r() for all the
details.
ARGUMENTS
- r1: the second of the two rotations being composed. The first rotation is an
identity, so it's not given
- out: optional argument specifying the destination. By default, a new numpy
array(s) is created and returned. To write the results into an existing (and
possibly non-contiguous) array, specify it with the 'out' kwarg. 'out' is the
one numpy array we will write into
RETURNED VALUE
We return a single array: dr01/dr0
- compose_rt(*rt, get_gradients=False, out=None)
- Compose rt transformations
SYNOPSIS
r10 = rotation_axis10 * rotation_magnitude10
r21 = rotation_axis21 * rotation_magnitude21
r32 = rotation_axis32 * rotation_magnitude32
rt10 = nps.glue(r10,t10, axis=-1)
rt21 = nps.glue(r21,t21, axis=-1)
rt32 = nps.glue(r32,t32, axis=-1)
print(rt10.shape)
===>
(6,)
rt30 = mrcal.compose_rt( rt32, rt21, rt10 )
print(x0.shape)
===>
(3,)
print( nps.norm2( mrcal.transform_point_rt(rt30, x0) -
mrcal.transform_point_rt(rt32,
mrcal.transform_point_rt(rt21,
mrcal.transform_point_rt(rt10, x0)))))
===>
0
print( [arr.shape for arr in mrcal.compose_rt(rt21,rt10,
get_gradients = True)] )
===>
[(6,), (6,6), (6,6)]
Given 2 or more rt transformations, returns their composition. An rt
transformation is a (6,) array formed by nps.glue(r,t, axis=-1) where r is a
(3,) Rodrigues vector and t is a (3,) translation vector. This transformation is
defined by a matrix multiplication and an addition. x and t are stored as a row
vector (that's how numpy stores 1-dimensional arrays), but the multiplication
works as if x was a column vector (to match linear algebra conventions):
transform_point_rt(rt, x) = transpose( matmult(R_from_r(rt[:3]), transpose(x)) +
transpose(rt[3,:]) ) =
= matmult(x, transpose(R_from_r(rt[:3]))) +
rt[3:]
By default this function returns the composed transformation only. If we also
want gradients, pass get_gradients=True. This is supported ONLY if we have
EXACTLY 2 transformations to compose. Logic:
if not get_gradients: return rt=compose(rt0,rt1)
else: return (rt=compose(rt0,rt1), dr/drt0, dr/drt1)
Note that the poseutils C API returns only
- dr_dr0
- dr_dr1
- dt_dr0
- dt_dt1
because
- dr/dt0 is always 0
- dr/dt1 is always 0
- dt/dr1 is always 0
- dt/dt0 is always the identity matrix
This Python function, however fills in those constants to return the full (and
more convenient) arrays.
This function supports broadcasting fully, so we can compose lots of
transformations at the same time.
In-place operation is supported; the output array may be the same as either of
the input arrays to overwrite the input.
ARGUMENTS
- *rt: a list of transformations to compose. Usually we'll be composing two
transformations, but any number could be given here. Each broadcasted slice
has shape (6,)
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of composed transformations. Otherwise we return a tuple of arrays of
composed transformations and their gradients. Gradient reporting is only
supported when exactly two transformations are given
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return an array of composed rt transformations. Each
broadcasted slice has shape (6,)
If get_gradients: we return a tuple of arrays containing the composed
transformations and the gradients (rt=compose(rt0,rt1),
drt/drt0,drt/drt1):
1. The composed transformation. Each broadcasted slice has shape (6,)
2. The gradient drt/dr0. Each broadcasted slice has shape (6,6). The first
dimension selects the element of rt, and the last dimension selects the
element of rt0
3. The gradient drt/drt1. Each broadcasted slice has shape (6,6). The first
dimension selects the element of rt, and the last dimension selects the
element of rt1
- compute_chessboard_corners(W, H, *, globs_per_camera=('*',), corners_cache_vnl=None, jobs=1, exclude_images=set(), weight_column_kind='level')
- Compute the chessboard observations and returns them in a usable form
SYNOPSIS
observations, indices_frame_camera, paths = \
mrcal.compute_chessboard_corners(10, 10,
globs_per_camera = ('frame*-cam0.jpg','frame*-cam1.jpg'),
corners_cache_vnl = "corners.vnl")
The input to a calibration problem is a set of images of a calibration object
from different angles and positions. This function ingests these images, and
outputs the detected chessboard corner coordinates in a form usable by the mrcal
optimization routines.
The "corners_cache_vnl" argument specifies a file containing cached results of
the chessboard detector. If this file already exists, we don't run the detector,
but just use the contents of the file. Otherwise, we run the detector, and store
the results here.
The "corner cache" file is a vnlog 3 or 4 columns. Each row describes a
chessboard corner. The first 3 columns are
# filename x y
If the 4th column is given, it usually is a 'level' or a 'weight'. It encodes
the confidence we have in that corner, and the exact interpretation is dependent
on the value of the 'weight_column_kind' argument. The output of this function
is an array with a weight for each point, so the logic serves to convert the
extra column to a weight.
if weight_column_kind == 'level': the 4th column is a decimation level of the
detected corner. If we needed to cut down the image resolution to detect a
corner, its coordinates are known less precisely, and we use that information
to weight the errors appropriately later. We set the output weight =
1/2^level. If the 4th column is '-' or <0, the given point was not detected,
and should be ignored: we set weight = -1
elif weight_column_kind == 'weight': the 4th column is already represented as a
weight, so I just copy it to the output. If the 4th column is '-' or <=0, the
given point was not detected, and should be ignored: we set weight = -1
elif weight_column_kind is None: I hard-code the output weight to 1.0. Any data
in the extra column is ignored
ARGUMENTS
- W, H: the width and height of the point grid in the calibration object we're
using
- globs_per_camera: a list of strings, one per camera, containing
globs_per_camera matching the image filenames for that camera. The filenames
are expected to encode the instantaneous frame numbers, with identical frame
numbers implying synchronized images. A common scheme is to name an image
taken by frame C at time T "frameT-camC.jpg". Then images frame10-cam0.jpg and
frame10-cam1.jpg are assumed to have been captured at the same moment in time
by cameras 0 and 1. With this scheme, if you wanted to calibrate these two
cameras together, you'd pass ('frame*-cam0.jpg','frame*-cam1.jpg') in the
"globs_per_camera" argument.
The "globs_per_camera" argument may be omitted. In this case all images are
mapped to the same camera.
- corners_cache_vnl: the name of a file to use to read/write the detected
corners; or a python file object to read data from. If the given file exists
or a python file object is given, we read the detections from it, and do not
run the detector. If the given file does NOT exist (which is what happens the
first time), mrgingham will be invoked to compute the corners from the images,
and the results will be written to that file. So the same function call can be
used to both compute the corners initially, and to reuse the pre-computed
corners with subsequent calls. This exists to save time where re-analyzing the
same data multiple times.
- jobs: a GNU-Make style parallelization flag. Indicates how many parallel
processes should be invoked when computing the corners. If given, a numerical
argument is required. If jobs<0: the corners_cache_vnl MUST already contain
valid data; if it doesn't, an exception is thrown instead of the corners being
recomputed.
- exclude_images: a set of filenames to exclude from reported results
- weight_column_kind: an optional argument, defaulting to 'level'. Selects the
interpretation of the 4th column describing each corner. Valid options are:
- 'level': the 4th column is a decimation level. Level-0 means
'full-resolution', level-1 means 'half-resolution' and so on. I set output
weight = 1/2^level. If the 4th column is '-' or <0, the given point was not
detected, and should be ignored: we set output weight = -1
- 'weight': the 4th column is already a weight; I copy it to the output. If
the 4th column is '-' or <0, the given point was not detected, and should be
ignored: we set output weight = -1
- None: the 4th column should be ignored, and I set the output weight to 1.0
RETURNED VALUES
This function returns a tuple (observations, indices_frame_camera, files_sorted)
- observations: an ordered (N,object_height_n,object_width_n,3) array describing
N board observations where the board has dimensions
(object_height_n,object_width_n) and each point is an (x,y,weight) pixel
observation. A weight<0 means "ignore this point". Incomplete chessboard
observations can be specified in this way.
- indices_frame_camera is an (N,2) array of contiguous, sorted integers where
each observation is (index_frame,index_camera)
- files_sorted is a list of paths of images corresponding to the observations
Note that this assumes we're solving a calibration problem (stationary cameras)
observing a moving object, so this returns indices_frame_camera. It is the
caller's job to convert this into indices_frame_camintrinsics_camextrinsics,
which mrcal.optimize() expects
- corresponding_icam_extrinsics(...)
- Return the icam_extrinsics corresponding to a given icam_intrinsics
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
icam_intrinsics = m.icam_intrinsics()
icam_extrinsics = \
mrcal.corresponding_icam_extrinsics(icam_intrinsics,
**optimization_inputs)
if icam_extrinsics >= 0:
extrinsics_rt_fromref_at_calibration_time = \
optimization_inputs['extrinsics_rt_fromref'][icam_extrinsics]
When calibrating cameras, each observations is associated with some camera
intrinsics (lens parameters) and some camera extrinsics (geometry). Those two
chunks of data live in different parts of the optimization vector, and are
indexed independently. If we have stationary cameras, then each set of camera
intrinsics is associated with exactly one set of camera extrinsics, and we can
use this function to query this correspondence. If we have moving cameras, then
a single physical camera would have one set of intrinsics but many different
extrinsics, and this function call will throw an exception.
Furthermore, it is possible that a camera's pose is used to define the reference
coordinate system of the optimization. In this case this camera has no explicit
extrinsics (they are an identity transfomration, by definition), and we return
-1, successfully.
In order to determine the camera mapping, we need quite a bit of context. If we
have the full set of inputs to the optimization function, we can pass in those
(as shown in the example above). Or we can pass the individual arguments that
are needed (see ARGUMENTS section for the full list). If the optimization inputs
and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- icam_intrinsics: an integer indicating which camera we're asking about
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- Ncameras_intrinsics
Ncameras_extrinsics
- Nobservations_board
- Nobservations_point
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
- indices_frame_camintrinsics_camextrinsics: array of dims (Nobservations_board,
3). For each observation these are an
(iframe,icam_intrinsics,icam_extrinsics) tuple. icam_extrinsics == -1
means this observation came from a camera in the reference coordinate system.
iframe indexes the "frames_rt_toref" array, icam_intrinsics indexes the
"intrinsics_data" array, icam_extrinsics indexes the "extrinsics_rt_fromref"
array
All of the indices are guaranteed to be monotonic. This array contains 32-bit
integers.
RETURNED VALUE
The integer reporting the index of the camera extrinsics in the optimization
vector. If this camera is at the reference of the coordinate system, return -1
- estimate_joint_frame_poses(calobject_Rt_camera_frame, extrinsics_Rt_fromref, indices_frame_camera, object_width_n, object_height_n, object_spacing)
- Estimate world-referenced poses of the calibration object
SYNOPSIS
print( calobject_Rt_camera_frame.shape )
===>
(123, 4,3)
print( extrinsics_Rt_fromref.shape )
===>
(2, 4,3)
# We have 3 cameras. The first one is at the reference coordinate system,
# the pose estimates of the other two are in this array
print( indices_frame_camera.shape )
===>
(123, 2)
frames_rt_toref = \
mrcal.estimate_joint_frame_poses(calobject_Rt_camera_frame,
extrinsics_Rt_fromref,
indices_frame_camera,
object_width_n, object_height_n,
object_spacing)
print( frames_rt_toref.shape )
===>
(87, 6)
# We have 123 observations of the calibration object by ANY camera. 87
# instances of time when the object was observed. Most of the time it was
# observed by multiple cameras simultaneously, hence 123 > 87
i_observation = 10
iframe,icam = indices_frame_camera[i_observation, :]
# The calibration object in its reference coordinate system
calobject = mrcal.ref_calibration_object(object_width_n,
object_height_n,
object_spacing)
# The estimated calibration object points in the reference coordinate
# system, for this one observation
pref = mrcal.transform_point_rt( frames_rt_toref[iframe],
calobject )
# The estimated calibration object points in the camera coord system. Camera
# 0 is at the reference
if icam >= 1:
pcam = mrcal.transform_point_Rt( extrinsics_Rt_fromref[icam-1],
pref )
else:
pcam = pref
# The pixel observations we would see if the pose estimates were correct
q = mrcal.project(pcam, *models[icam].intrinsics())
# The reprojection error, comparing these hypothesis pixel observations from
# what we actually observed. This should be small
err = q - observations[i_observation][:2]
print( np.linalg.norm(err) )
===>
[something small]
mrcal solves camera calibration problems by iteratively optimizing a nonlinear
least squares problem to bring the pixel observation predictions in line with
actual pixel observations. This requires an initial "seed", an initial estimate
of the solution. This function is a part of that computation. Since this is just
an initial estimate that will be refined, the results of this function do not
need to be exact.
This function ingests an estimate of the camera poses in respect to each other,
and the estimate of the calibration objects in respect to the observing camera.
Most of the time we have simultaneous calibration object observations from
multiple cameras, so this function consolidates all this information to produce
poses of the calibration object in the reference coordinate system, NOT the
observing-camera coordinate system poses we already have.
By convention, we have a "reference" coordinate system that ties the poses of
all the frames (calibration objects) and the cameras together. And by
convention, this "reference" coordinate system is the coordinate system of
camera 0. Thus the array of camera poses extrinsics_Rt_fromref holds Ncameras-1
transformations: the first camera has an identity transformation, by definition.
This function assumes we're observing a moving object from stationary cameras
(i.e. a vanilla camera calibration problem). The mrcal solver is more general,
and supports moving cameras, hence it uses a more general
indices_frame_camintrinsics_camextrinsics array instead of the
indices_frame_camera array used here.
ARGUMENTS
- calobject_Rt_camera_frame: an array of shape (Nobservations,4,3). Each slice
is an Rt transformation TO the observing camera coordinate system FROM the
calibration object coordinate system. This is returned by
estimate_monocular_calobject_poses_Rt_tocam()
- extrinsics_Rt_fromref: an array of shape (Ncameras-1,4,3). Each slice is an Rt
transformation TO the camera coordinate system FROM the reference coordinate
system. By convention camera 0 defines the reference coordinate system, so
that camera's extrinsics are the identity, by definition, and we don't store
that data in this array
- indices_frame_camera: an array of shape (Nobservations,2) and dtype
numpy.int32. Each row (iframe,icam) represents an observation at time
instant iframe of a calibration object by camera icam
- object_width_n: number of horizontal points in the calibration object grid
- object_height_n: number of vertical points in the calibration object grid
- object_spacing: the distance between adjacent points in the calibration
object. A square object is assumed, so the vertical and horizontal distances
are assumed to be identical
RETURNED VALUE
An array of shape (Nframes,6). Each slice represents the pose of the calibration
object at one instant in time: an rt transformation TO the reference coordinate
system FROM the calibration object coordinate system.
- estimate_monocular_calobject_poses_Rt_tocam(indices_frame_camera, observations, object_spacing, models_or_intrinsics)
- Estimate camera-referenced poses of the calibration object from monocular views
SYNOPSIS
print( indices_frame_camera.shape )
===>
(123, 2)
print( observations.shape )
===>
(123, 3)
models = [mrcal.cameramodel(f) for f in ("cam0.cameramodel",
"cam1.cameramodel")]
# Estimated poses of the calibration object from monocular observations
Rt_camera_frame = \
mrcal.estimate_monocular_calobject_poses_Rt_tocam( indices_frame_camera,
observations,
object_spacing,
models)
print( Rt_camera_frame.shape )
===>
(123, 4, 3)
i_observation = 10
icam = indices_frame_camera[i_observation,1]
# The calibration object in its reference coordinate system
calobject = mrcal.ref_calibration_object(object_width_n,
object_height_n,
object_spacing)
# The estimated calibration object points in the observing camera coordinate
# system
pcam = mrcal.transform_point_Rt( Rt_camera_frame[i_observation],
calobject )
# The pixel observations we would see if the calibration object pose was
# where it was estimated to be
q = mrcal.project(pcam, *models[icam].intrinsics())
# The reprojection error, comparing these hypothesis pixel observations from
# what we actually observed. We estimated the calibration object pose from
# the observations, so this should be small
err = q - observations[i_observation][:2]
print( np.linalg.norm(err) )
===>
[something small]
mrcal solves camera calibration problems by iteratively optimizing a nonlinear
least squares problem to bring the pixel observation predictions in line with
actual pixel observations. This requires an initial "seed", an initial estimate
of the solution. This function is a part of that computation. Since this is just
an initial estimate that will be refined, the results of this function do not
need to be exact.
We have pixel observations of a known calibration object, and we want to
estimate the pose of this object in the coordinate system of the camera that
produced these observations. This function ingests a number of such
observations, and solves this "PnP problem" separately for each one. The
observations may come from any lens model; everything is reprojected to a
pinhole model first to work with OpenCV. This function is a wrapper around the
solvePnP() openCV call, which does all the work.
ARGUMENTS
- indices_frame_camera: an array of shape (Nobservations,2) and dtype
numpy.int32. Each row (iframe,icam) represents an observation of a
calibration object by camera icam. iframe is not used by this function
- observations: an array of shape
(Nobservations,object_height_n,object_width_n,3). Each observation corresponds
to a row in indices_frame_camera, and contains a row of shape (3,) for each
point in the calibration object. Each row is (x,y,weight) where x,y are the
observed pixel coordinates. Any point where x<0 or y<0 or weight<0 is ignored.
This is the only use of the weight in this function.
- object_spacing: the distance between adjacent points in the calibration
object. A square object is assumed, so the vertical and horizontal distances
are assumed to be identical. Usually we need the object dimensions in the
object_height_n,object_width_n arguments, but here we get those from the shape
of the observations array
- models_or_intrinsics: either
- a list of mrcal.cameramodel objects from which we use the intrinsics
- a list of (lensmodel,intrinsics_data) tuples
These are indexed by icam from indices_frame_camera
RETURNED VALUE
An array of shape (Nobservations,4,3). Each slice is an Rt transformation TO the
camera coordinate system FROM the calibration object coordinate system.
- fitted_gaussian_equation(*, binwidth, x=None, mean=None, sigma=None, N=None, legend=None)
- Get an 'equation' gnuplotlib expression for a gaussian curve fitting some data
SYNOPSIS
import gnuplotlib as gp
import numpy as np
...
# x is a one-dimensional array with samples that we want to compare to a
# normal distribution. For instance:
# x = np.random.randn(10000) * 0.1 + 10
binwidth = 0.01
equation = \
mrcal.fitted_gaussian_equation(x = x,
binwidth = binwidth)
gp.plot(x,
histogram = True,
binwidth = binwidth,
equation_above = equation)
# A plot pops ups displaying a histogram of the array x overlaid by an ideal
# gaussian probability density function. This PDF corresponds to the mean
# and standard deviation of the data, and takes into account the histogram
# parameters to overlay nicely on top of it
Overlaying a ideal PDF on top of an empirical histogram requires a bit of math
to figure out the proper vertical scaling of the plotted PDF that would line up
with the histogram. This is evaluated by this function.
This function can be called in one of two ways:
- Passing the data in the 'x' argument. The statistics are computed from the
data, and there's no reason to pass 'mean', 'sigma', 'N'
- Passing the statistics 'mean', 'sigma', 'N' instead of the data 'x'. This is
useful to compare an empirical histogram with idealized distributions that are
expected to match the data, but do not. For instance, we may want to plot the
expected standard deviation that differs from the observed standard deviation
ARGUMENTS
- binwidth: the width of each bin in the histogram we will plot. This is the
only required argument
- x: one-dimensional numpy array containing the data that will be used to
construct the histogram. If given, (mean, sigma, N) must all NOT be given:
they will be computed from x. If omitted, then all those must be given instead
- mean: mean the gaussian to plot. Must be given if and only if x is not given
- sigma: standard deviation of the gaussian to plot. Must be given if and only
if x is not given
- N: the number of values in the dataset in the histogram. Must be given if and
only if x is not given
- legend: string containing the legend of the curve in the plot. May be omitted
or None to leave the curve unlabelled
RETURNED VALUES
String passable to gnuplotlib in the 'equation' or 'equation_above' plot option
- hypothesis_board_corner_positions(icam_intrinsics=None, idx_inliers=None, **optimization_inputs)
- Reports the 3D chessboard points observed by a camera at calibration time
SYNOPSIS
model = mrcal.cameramodel("xxx.cameramodel")
optimization_inputs = model.optimization_inputs()
# shape (Nobservations, Nheight, Nwidth, 3)
pcam = mrcal.hypothesis_board_corner_positions(**optimization_inputs)[0]
i_intrinsics = \
optimization_inputs['indices_frame_camintrinsics_camextrinsics'][:,1]
# shape (Nobservations,1,1,Nintrinsics)
intrinsics = nps.mv(optimization_inputs['intrinsics'][i_intrinsics],-2,-4)
optimization_inputs['observations_board'][...,:2] = \
mrcal.project( pcam,
optimization_inputs['lensmodel'],
intrinsics )
# optimization_inputs now contains perfect, noiseless board observations
x = mrcal.optimizer_callback(**optimization_inputs)[1]
print(nps.norm2(x[:mrcal.num_measurements_boards(**optimization_inputs)]))
==>
0
The optimization routine generates hypothetical observations from a set of
parameters being evaluated, trying to match these hypothetical observations to
real observations. To facilitate analysis, this routine returns these
hypothetical coordinates of the chessboard corners being observed. This routine
reports the 3D points in the coordinate system of the observing camera.
The hypothetical points are constructed from
- The calibration object geometry
- The calibration object-reference transformation in
optimization_inputs['frames_rt_toref']
- The camera extrinsics (reference-camera transformation) in
optimization_inputs['extrinsics_rt_fromref']
- The table selecting the camera and calibration object frame for each
observation in
optimization_inputs['indices_frame_camintrinsics_camextrinsics']
ARGUMENTS
- icam_intrinsics: optional integer specifying which intrinsic camera in the
optimization_inputs we're looking at. If omitted (or None), we report
camera-coordinate points for all the cameras
- idx_inliers: optional numpy array of booleans of shape
(Nobservations,object_height,object_width) to select the outliers manually. If
omitted (or None), the outliers are selected automatically: idx_inliers =
observations_board[...,2] > 0. This argument is available to pick common
inliers from two separate solves.
- **optimization_inputs: a dict() of arguments passable to mrcal.optimize() and
mrcal.optimizer_callback(). We use the geometric data. This dict is obtainable
from a cameramodel object by calling cameramodel.optimization_inputs()
RETURNED VALUE
- An array of shape (Nobservations, Nheight, Nwidth, 3) containing the
coordinates (in the coordinate system of each camera) of the chessboard
corners, for ALL the cameras. These correspond to the observations in
optimization_inputs['observations_board'], which also have shape
(Nobservations, Nheight, Nwidth, 3)
- An array of shape (Nobservations_thiscamera, Nheight, Nwidth, 3) containing
the coordinates (in the camera coordinate system) of the chessboard corners,
for the particular camera requested in icam_intrinsics. If icam_intrinsics is
None: this is the same array as the previous returned value
- an (N,3) array containing camera-frame 3D points observed at calibration time,
and accepted by the solver as inliers. This is a subset of the 2nd returned
array.
- an (N,3) array containing camera-frame 3D points observed at calibration time,
but rejected by the solver as outliers. This is a subset of the 2nd returned
array.
- identity_R(...)
- Return an identity rotation matrix
SYNOPSIS
print( mrcal.identity_R() )
===>
[[1. 0. 0.]
[0. 1. 0.]
[0. 0. 1.]]
As with all the poseutils functions, the output can be written directly into a
(possibly-non-contiguous) array, by specifying the destination in the 'out'
kwarg
- identity_Rt(...)
- Return an identity Rt transformation
SYNOPSIS
print( mrcal.identity_Rt() )
===>
[[1. 0. 0.]
[0. 1. 0.]
[0. 0. 1.]
[0. 0. 0.]]
As with all the poseutils functions, the output can be written directly into a
(possibly-non-contiguous) array, by specifying the destination in the 'out'
kwarg
- identity_r(...)
- Return an identity Rodrigues rotation
SYNOPSIS
print( mrcal.identity_r() )
===>
[0. 0. 0.]
As with all the poseutils functions, the output can be written directly into a
(possibly-non-contiguous) array, by specifying the destination in the 'out'
kwarg
- identity_rt(...)
- Return an identity rt transformation
SYNOPSIS
print( mrcal.identity_rt() )
===>
[0. 0. 0. 0. 0. 0.]
As with all the poseutils functions, the output can be written directly into a
(possibly-non-contiguous) array, by specifying the destination in the 'out'
kwarg
- image_transformation_map(model_from, model_to, *, intrinsics_only=False, distance=None, plane_n=None, plane_d=None, mask_valid_intrinsics_region_from=False)
- Compute a reprojection map between two models
SYNOPSIS
model_orig = mrcal.cameramodel("xxx.cameramodel")
image_orig = mrcal.load_image("image.jpg")
model_pinhole = mrcal.pinhole_model_for_reprojection(model_orig,
fit = "corners")
mapxy = mrcal.image_transformation_map(model_orig, model_pinhole,
intrinsics_only = True)
image_undistorted = mrcal.transform_image(image_orig, mapxy)
# image_undistorted is now a pinhole-reprojected version of image_orig
Returns the transformation that describes a mapping
- from pixel coordinates of an image of a scene observed by model_to
- to pixel coordinates of an image of the same scene observed by model_from
This transformation can then be applied to a whole image by calling
mrcal.transform_image().
This function returns a transformation map in an (Nheight,Nwidth,2) array. The
image made by model_to will have shape (Nheight,Nwidth). Each pixel (x,y) in
this image corresponds to a pixel mapxy[y,x,:] in the image made by model_from.
One application of this function is to validate the models in a stereo pair. For
instance, reprojecting one camera's image at distance=infinity should produce
exactly the same image that is observed by the other camera when looking at very
far objects, IF the intrinsics and rotation are correct. If the images don't
line up well, we know that some part of the models is off. Similarly, we can use
big planes (such as observations of the ground) and plane_n, plane_d to validate.
This function has several modes of operation:
- intrinsics, extrinsics
Used if not intrinsics_only and \
plane_n is None and \
plane_d is None
This is the default. For each pixel in the output, we use the full model to
unproject a given distance out, and then use the full model to project back
into the other camera.
- intrinsics only
Used if intrinsics_only and \
plane_n is None and \
plane_d is None
Similar, but the extrinsics are ignored. We unproject the pixels in one model,
and project the into the other camera. The two camera coordinate systems are
assumed to line up perfectly
- plane
Used if plane_n is not None and
plane_d is not None
We map observations of a given plane in camera FROM coordinates coordinates to
where this plane would be observed by camera TO. We unproject each pixel in
one camera, compute the intersection point with the plane, and project that
intersection point back to the other camera. This uses ALL the intrinsics,
extrinsics and the plane representation. The plane is represented by a normal
vector plane_n, and the distance to the normal plane_d. The plane is all
points p such that inner(p,plane_n) = plane_d. plane_n does not need to be
normalized; any scaling is compensated in plane_d.
ARGUMENTS
- model_from: the mrcal.cameramodel object describing the camera used to capture
the input image. We always use the intrinsics. if not intrinsics_only: we use
the extrinsics also
- model_to: the mrcal.cameramodel object describing the camera that would have
captured the image we're producing. We always use the intrinsics. if not
intrinsics_only: we use the extrinsics also
- intrinsics_only: optional boolean, defaulting to False. If False: we respect
the relative transformation in the extrinsics of the camera models.
- distance: optional value, defaulting to None. Used only if not
intrinsics_only. We reproject points in space a given distance out. If
distance is None (the default), we look out to infinity. This is equivalent to
using only the rotation component of the extrinsics, ignoring the translation.
- plane_n: optional numpy array of shape (3,); None by default. If given, we
produce a transformation to map observations of a given plane to the same
pixels in the source and target images. This argument describes the normal
vector in the coordinate system of model_from. The plane is all points p such
that inner(p,plane_n) = plane_d. plane_n does not need to be normalized; any
scaling is compensated in plane_d. If given, plane_d should be given also, and
intrinsics_only should be False. if given, we use the full intrinsics and
extrinsics of both camera models
- plane_d: optional floating-point value; None by default. If given, we produce
a transformation to map observations of a given plane to the same pixels in
the source and target images. The plane is all points p such that
inner(p,plane_n) = plane_d. plane_n does not need to be normalized; any
scaling is compensated in plane_d. If given, plane_n should be given also, and
intrinsics_only should be False. if given, we use the full intrinsics and
extrinsics of both camera models
- mask_valid_intrinsics_region_from: optional boolean defaulting to False. If
True, points outside the valid-intrinsics region in the FROM image are set to
black, and thus do not appear in the output image
RETURNED VALUE
A numpy array of shape (Nheight,Nwidth,2) where Nheight and Nwidth represent the
imager dimensions of model_to. This array contains 32-bit floats, as required by
cv2.remap() (the function providing the internals of mrcal.transform_image()).
This array can be passed to mrcal.transform_image()
- imagergrid_using(imagersize, gridn_width, gridn_height=None)
- Get a 'using' gnuplotlib expression for imager colormap plots
SYNOPSIS
import gnuplotlib as gp
import numpy as np
import mrcal
...
Nwidth = 60
Nheight = 40
# shape (Nheight,Nwidth,3)
v,_ = \
mrcal.sample_imager_unproject(Nw, Nh,
*model.imagersize(),
*model.intrinsics())
# shape (Nheight,Nwidth)
f = interesting_quantity(v)
gp.plot(f,
tuplesize = 3,
ascii = True,
using = mrcal.imagergrid_using(model.imagersize, Nw, Nh),
square = True,
_with = 'image')
We often want to plot some quantity at every location on the imager (intrinsics
uncertainties for instance). This is done by gridding the imager, computing the
quantity at each grid point, and sending this to gnuplot. This involves a few
non-obvious plotting idioms, with the full usage summarized in the above
example.
Due to peculiarities of gnuplot, the 'using' expression produced by this
function can only be used in plots using ascii data commands (i.e. pass
'ascii=True' to gnuplotlib).
ARGUMENTS
- imagersize: a (width,height) tuple for the size of the imager. With a
mrcal.cameramodel object this is model.imagersize()
- gridn_width: how many points along the horizontal gridding dimension
- gridn_height: how many points along the vertical gridding dimension. If
omitted or None, we compute an integer gridn_height to maintain a square-ish
grid: gridn_height/gridn_width ~ imager_height/imager_width
RETURNED VALUE
The 'using' string.
- implied_Rt10__from_unprojections(q0, p0, v1, *, weights=None, atinfinity=True, focus_center=array([0., 0.]), focus_radius=100000000.0)
- Compute the implied-by-the-intrinsics transformation to fit two cameras' projections
SYNOPSIS
models = ( mrcal.cameramodel('cam0-dance0.cameramodel'),
mrcal.cameramodel('cam0-dance1.cameramodel') )
lensmodels = [model.intrinsics()[0] for model in models]
intrinsics_data = [model.intrinsics()[1] for model in models]
# v shape (...,Ncameras,Nheight,Nwidth,...)
# q0 shape (..., Nheight,Nwidth,...)
v,q0 = \
mrcal.sample_imager_unproject(60, None,
*models[0].imagersize(),
lensmodels, intrinsics_data,
normalize = True)
implied_Rt10 = \
mrcal.implied_Rt10__from_unprojections(q0, v[0,...], v[1,...])
q1 = mrcal.project( mrcal.transform_point_Rt(implied_Rt10, v[0,...]),
*models[1].intrinsics())
projection_diff = q1 - q0
When comparing projections from two lens models, it is usually necessary to
align the geometry of the two cameras, to cancel out any transformations implied
by the intrinsics of the lenses. This transformation is computed by this
function, used primarily by mrcal.show_projection_diff() and the
mrcal-show-projection-diff tool.
What are we comparing? We project the same world point into the two cameras, and
report the difference in projection. Usually, the lens intrinsics differ a bit,
and the implied origin of the camera coordinate systems and their orientation
differ also. These geometric uncertainties are baked into the intrinsics. So
when we project "the same world point" we must apply a geometric transformation
to compensate for the difference in the geometry of the two cameras. This
transformation is unknown, but we can estimate it by fitting projections across
the imager: the "right" transformation would result in apparent low projection
diffs in a wide area.
The primary inputs are unprojected gridded samples of the two imagers, obtained
with something like mrcal.sample_imager_unproject(). We grid the two imagers,
and produce normalized observation vectors for each grid point. We pass the
pixel grid from camera0 in q0, and the two unprojections in p0, v1. This
function then tries to find a transformation to minimize
norm2( project(camera1, transform(p0)) - q1 )
We return an Rt transformation to map points in the camera0 coordinate system to
the camera1 coordinate system. Some details about this general formulation are
significant:
- The subset of points we use for the optimization
- What kind of transformation we use
In most practical usages, we would not expect a good fit everywhere in the
imager: areas where no chessboards were observed will not fit well, for
instance. From the point of view of the fit we perform, those ill-fitting areas
should be treated as outliers, and they should NOT be a part of the solve. How
do we specify the well-fitting area? The best way is to use the model
uncertainties to pass the weights in the "weights" argument (see
show_projection_diff() for an implementation). If uncertainties aren't
available, or if we want a faster solve, the focus region can be passed in the
focus_center, focus_radius arguments. By default, these are set to encompass the
whole imager, since the uncertainties would take care of everything, but without
uncertainties (weights = None), these should be set more discriminately. It is
possible to pass both a focus region and weights, but it's probably not very
useful.
Unlike the projection operation, the diff operation is NOT invariant under
geometric scaling: if we look at the projection difference for two points at
different locations along a single observation ray, there will be a variation in
the observed diff. This is due to the geometric difference in the two cameras.
If the models differed only in their intrinsics parameters, then this would not
happen. Thus this function needs to know how far from the camera it should look.
By default (atinfinity = True) we look out to infinity. In this case, p0 is
expected to contain unit vectors. To use any other distance, pass atinfinity =
False, and pass POINTS in p0 instead of just observation directions. v1 should
always be normalized. Generally the most confident distance will be where the
chessboards were observed at calibration time.
Practically, it is very easy for the unprojection operation to produce nan or
inf values. And the weights could potentially have some invalid values also.
This function explicitly checks for such illegal data in p0, v1 and weights, and
ignores those points.
ARGUMENTS
- q0: an array of shape (Nh,Nw,2). Gridded pixel coordinates covering the imager
of both cameras
- p0: an array of shape (...,Nh,Nw,3). An unprojection of q0 from camera 0. If
atinfinity, this should contain unit vectors, else it should contain points in
space at the desired distance from the camera. This array may have leading
dimensions that are all used in the fit. These leading dimensions correspond
to those in the "weights" array
- v1: an array of shape (Nh,Nw,3). An unprojection of q0 from camera 1. This
should always contain unit vectors, regardless of the value of atinfinity
- weights: optional array of shape (...,Nh,Nw); None by default. If given, these
are used to weigh each fitted point differently. Usually we use the projection
uncertainties to apply a stronger weight to more confident points. If omitted
or None, we weigh each point equally. This array may have leading dimensions
that are all used in the fit. These leading dimensions correspond to those in
the "p0" array
- atinfinity: optional boolean; True by default. If True, we're looking out to
infinity, and I compute a rotation-only fit; a full Rt transformation is still
returned, but Rt[3,:] is 0; p0 should contain unit vectors. If False, I'm
looking out to a finite distance, and p0 should contain 3D points specifying
the positions of interest.
- focus_center: optional array of shape (2,); (0,0) by default. Used to indicate
that we're interested only in a subset of pixels q0, a distance focus_radius
from focus_center. By default focus_radius is LARGE, so we use all the points.
This is intended to be used if no uncertainties are available, and we need to
manually select the focus region.
- focus_radius: optional value; LARGE by default. Used to indicate that we're
interested only in a subset of pixels q0, a distance focus_radius from
focus_center. By default focus_radius is LARGE, so we use all the points. This
is intended to be used if no uncertainties are available, and we need to
manually select the focus region.
RETURNED VALUE
An array of shape (4,3), representing an Rt transformation from camera0 to
camera1. If atinfinity then we're computing a rotation-fit only, but we still
report a full Rt transformation with the t component set to 0
- ingest_packed_state(b_packed, **optimization_inputs)
- Read a given packed state into optimization_inputs
SYNOPSIS
# A simple gradient check
model = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = model.optimization_inputs()
b0,x0,J = mrcal.optimizer_callback(no_factorization = True,
**optimization_inputs)[:3]
db = np.random.randn(len(b0)) * 1e-9
mrcal.ingest_packed_state(b0 + db,
**optimization_inputs)
x1 = mrcal.optimizer_callback(no_factorization = True,
no_jacobian = True,
**optimization_inputs)[1]
dx_observed = x1 - x0
dx_predicted = nps.inner(J, db_packed)
This is the converse of mrcal.optimizer_callback(). One thing
mrcal.optimizer_callback() does is to convert the expanded (intrinsics,
extrinsics, ...) arrays into a 1-dimensional scaled optimization vector
b_packed. mrcal.ingest_packed_state() allows updates to b_packed to be absorbed
back into the (intrinsics, extrinsics, ...) arrays for further evaluation with
mrcal.optimizer_callback() and others.
ARGUMENTS
- b_packed: a numpy array of shape (Nstate,) containing the input packed state
- **optimization_inputs: a dict() of arguments passable to mrcal.optimize() and
mrcal.optimizer_callback(). The arrays in this dict are updated
RETURNED VALUE
None
- invert_R(R, *, out=None)
- Invert a rotation matrix
SYNOPSIS
print(R.shape)
===>
(3,3)
R10 = mrcal.invert_R(R01)
print(x1.shape)
===>
(3,)
x0 = mrcal.rotate_point_R(R01, x1)
print( nps.norm2( x1 - \
mrcal.rotate_point_R(R10, x0) ))
===>
0
Given a rotation specified as a (3,3) rotation matrix outputs another rotation
matrix that has the opposite effect. This is simply a matrix transpose.
This function supports broadcasting fully.
In-place operation is supported; the output array may be the same as the input
array to overwrite the input.
ARGUMENTS
- R: array of shape (3,3), a rotation matrix. It is assumed that this is a valid
rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that is not checked
- out: optional argument specifying the destination. By default, a new numpy
array is created and returned. To write the results into an existing (and
possibly non-contiguous) array, specify it with the 'out' kwarg. If 'out' is
given, we return the 'out' that was passed in. This is the standard behavior
provided by numpysane_pywrap.
RETURNED VALUE
The inverse rotation matrix in an array of shape (3,3).
- invert_Rt(Rt, *, out=None)
- Invert an Rt transformation
SYNOPSIS
Rt01 = nps.glue(rotation_matrix,translation, axis=-2)
print(Rt01.shape)
===>
(4,3)
Rt10 = mrcal.invert_Rt(Rt01)
print(x1.shape)
===>
(3,)
x0 = mrcal.transform_point_Rt(Rt01, x1)
print( nps.norm2( x1 - \
mrcal.transform_point_Rt(Rt10, x0) ))
===>
0
Given an Rt transformation to convert a point representated in coordinate system
1 to coordinate system 0 (let's call it Rt01), returns a transformation that
does the reverse: converts a representation in coordinate system 0 to coordinate
system 1 (let's call it Rt10).
Thus if you have a point in coordinate system 1 (let's call it x1), we can
convert it to a representation in system 0, and then back. And we'll get the
same thing out:
x1 == mrcal.transform_point_Rt( mrcal.invert_Rt(Rt01),
mrcal.transform_point_Rt( Rt01, x1 ))
An Rt transformation represents a rotation and a translation. It is a (4,3)
array formed by nps.glue(R,t, axis=-2) where R is a (3,3) rotation matrix and t
is a (3,) translation vector.
Applied to a point x the transformed result is rotate(x)+t. Given a matrix R,
the rotation is defined by a matrix multiplication. x and t are stored as a row
vector (that's how numpy stores 1-dimensional arrays), but the multiplication
works as if x was a column vector (to match linear algebra conventions). See the
docs for mrcal._transform_point_Rt() for more detail.
This function supports broadcasting fully.
In-place operation is supported; the output array may be the same as the input
array to overwrite the input.
ARGUMENTS
- Rt: array of shape (4,3). This matrix defines the transformation. Rt[:3,:] is
a rotation matrix; Rt[3,:] is a translation. It is assumed that the rotation
matrix is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that
is not checked
- out: optional argument specifying the destination. By default, a new numpy
array is created and returned. To write the results into an existing (and
possibly non-contiguous) array, specify it with the 'out' kwarg. If 'out' is
given, we return the 'out' that was passed in. This is the standard behavior
provided by numpysane_pywrap.
RETURNED VALUE
The inverse Rt transformation in an array of shape (4,3).
- invert_rt(rt, *, get_gradients=False, out=None)
- Invert an rt transformation
SYNOPSIS
r = rotation_axis * rotation_magnitude
rt01 = nps.glue(r,t, axis=-1)
print(rt01.shape)
===>
(6,)
rt10 = mrcal.invert_rt(rt01)
print(x1.shape)
===>
(3,)
x0 = mrcal.transform_point_rt(rt01, x1)
print( nps.norm2( x1 -
mrcal.transform_point_rt(rt10, x0) ))
===>
0
Given an rt transformation to convert a point representated in coordinate system
1 to coordinate system 0 (let's call it rt01), returns a transformation that
does the reverse: converts a representation in coordinate system 0 to coordinate
system 1 (let's call it rt10).
Thus if you have a point in coordinate system 1 (let's call it x1), we can
convert it to a representation in system 0, and then back. And we'll get the
same thing out:
x1 == mrcal.transform_point_rt( mrcal.invert_rt(rt01),
mrcal.transform_point_rt( rt01, x1 ))
An rt transformation represents a rotation and a translation. It is a (6,) array
formed by nps.glue(r,t, axis=-1) where r is a (3,) Rodrigues vector and t is a
(3,) translation vector.
Applied to a point x the transformed result is rotate(x)+t. x and t are stored
as a row vector (that's how numpy stores 1-dimensional arrays). See the docs for
mrcal._transform_point_rt() for more detail.
By default this function returns the rt transformation only. If we also want
gradients, pass get_gradients=True. Logic:
if not get_gradients: return rt
else: return (rt, drtout_drtin)
Note that the poseutils C API returns only
- dtout_drin
- dtout_dtin
because
- drout_drin is always -I
- drout_dtin is always 0
This Python function, however fills in those constants to return the full (and
more convenient) arrays.
This function supports broadcasting fully.
In-place operation is supported; the output array may be the same as the input
array to overwrite the input.
ARGUMENTS
- rt: array of shape (6,). This vector defines the input transformation. rt[:3]
is a rotation defined as a Rodrigues vector; rt[3:] is a translation.
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of rt translation. Otherwise we return a tuple of arrays of rt
translations and their gradients.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return an array of rt transformation(s). Each
broadcasted slice has shape (6,)
If get_gradients: we return a tuple of arrays containing the rt transformation(s)
and the gradients (rt, drtout/drtin)
1. The rt transformation. Each broadcasted slice has shape (6,)
2. The gradient drtout/drtin. Each broadcasted slice has shape (6,6). The first
dimension selects elements of rtout, and the last dimension selects elements
of rtin
- is_within_valid_intrinsics_region(q, model)
- Which of the pixel coordinates fall within the valid-intrinsics region?
SYNOPSIS
mask = mrcal.is_within_valid_intrinsics_region(q, model)
q_trustworthy = q[mask]
mrcal camera models may have an estimate of the region of the imager where the
intrinsics are trustworthy (originally computed with a low-enough error and
uncertainty). When using a model, we may want to process points that fall
outside of this region differently from points that fall within this region.
This function returns a mask that indicates whether each point is within the
region or not.
If no valid-intrinsics region is defined in the model, returns None.
ARGUMENTS
- q: an array of shape (..., 2) of pixel coordinates
- model: the model we're interrogating
RETURNED VALUE
The mask that indicates whether each point is within the region
- knots_for_splined_models(...)
- Return a tuple of locations of x and y spline knots
SYNOPSIS
print(mrcal.knots_for_splined_models('LENSMODEL_SPLINED_STEREOGRAPHIC_order=2_Nx=4_Ny=3_fov_x_deg=200'))
( array([-3.57526078, -1.19175359, 1.19175359, 3.57526078]),
array([-2.38350719, 0. , 2.38350719]))
Splined models are defined by the locations of their control points. These are
arranged in a grid, the size and density of which is set by the model
configuration. This function returns a tuple:
- the locations of the knots along the x axis
- the locations of the knots along the y axis
The values in these arrays correspond to whatever is used to index the splined
surface. In the case of LENSMODEL_SPLINED_STEREOGRAPHIC, these are the
normalized stereographic projection coordinates. These can be unprojected to
observation vectors at the knots:
ux,uy = mrcal.knots_for_splined_models('LENSMODEL_SPLINED_STEREOGRAPHIC_order=2_Nx=4_Ny=3_fov_x_deg=200')
u = np.ascontiguousarray(nps.mv(nps.cat(*np.meshgrid(ux,uy)), 0, -1))
v = mrcal.unproject_stereographic(u)
# v[index_y, index_x] is now an observation vector that will project to this
# knot
ARGUMENTS
- lensmodel: the "LENSMODEL_..." string we're querying. This function only makes
sense for "LENSMODEL_SPLINED_..." models
RETURNED VALUE
A tuple:
- An array of shape (Nx,) representing the knot locations along the x axis
- An array of shape (Ny,) representing the knot locations along the y axis
- lensmodel_metadata_and_config(...)
- Returns a model's meta-information and configuration
SYNOPSIS
import pprint
pprint.pprint(mrcal.lensmodel_metadata_and_config('LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=14_fov_x_deg=200'))
{'Nx': 16,
'Ny': 14,
'can_project_behind_camera': 1,
'fov_x_deg': 200,
'has_core': 1,
'has_gradients': 1,
'order': 3}
Each lens model has some metadata (inherent properties of a model family) and
may have some configuration (parameters that specify details about the model,
but aren't subject to optimization). The configuration parameters are embedded
in the model string. This function returns a dict containing the metadata and
all the configuration values. See the documentation for details:
http://mrcal.secretsauce.net/lensmodels.html#representation
ARGUMENTS
- lensmodel: the "LENSMODEL_..." string we're querying
RETURNED VALUE
A dict containing all the metadata and configuration properties for that model
- lensmodel_num_params(...)
- Get the number of lens parameters for a particular model type
SYNOPSIS
print(mrcal.lensmodel_num_params('LENSMODEL_OPENCV4'))
8
I support a number of lens models, which have different numbers of parameters.
Given a lens model, this returns how many parameters there are. Some models have
no configuration, and there's a static mapping between the lensmodel string and
the parameter count. Some other models DO have some configuration values inside
the model string (LENSMODEL_SPLINED_STEREOGRAPHIC_... for instance), and the
number of parameters is computed using the configuration values. The lens model
is given as a string such as
LENSMODEL_PINHOLE
LENSMODEL_OPENCV4
LENSMODEL_CAHVOR
LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=12_fov_x_deg=100
The full list can be obtained with mrcal.supported_lensmodels()
Note that when optimizing a lens model, some lens parameters may be locked down,
resulting in fewer parameters than this function returns. To retrieve the number
of parameters used to represent the intrinsics of a camera in an optimization,
call mrcal.num_intrinsics_optimization_params(). Or to get the number of
parameters used to represent the intrinsics of ALL the cameras in an
optimization, call mrcal.num_states_intrinsics()
ARGUMENTS
- lensmodel: the "LENSMODEL_..." string we're querying
RETURNED VALUE
An integer number of parameters needed to describe a lens of the given type
- load_image(...)
- Load an image from disk into a numpy array
SYNOPSIS
image = \
mrcal.load_image("scene.jpg",
bits_per_pixel = 8,
channels = 1)
## image is now a numpy array of shape (height,width) containing the
## pixel data
This is a completely uninteresting image-loading routine. It's like any other
image-loading routine out there; use any that you like. This exists because cv2
is very slow.
This wraps the mrcal_image_TYPE_load() functions. At this time I support only
these 3 data formats:
- bits_per_pixel = 8, channels = 1: 8-bit grayscale data
- bits_per_pixel = 16, channels = 1: 16-bit grayscale data
- bits_per_pixel = 24, channels = 3: BGR color data
With the exception of 16-bit grayscale data, the load function will convert the
input image to the requested format. At this time, loading 16-bit grayscale data
requires that the input image matches that format.
If the bits_per_pixel, channels arguments are omitted or set to <= 0, we will
load the image in whatever format it appears on disk.
ARGUMENTS
- filename: the image on disk to load
- bits_per_pixel: optional integer describing the requested bit depth. Must be 8
or 16 or 24. If omitted or <= 0, we use the bit depth of the image on disk
- channels: optional integer describing the number of channels in the image.
Integer. Must be 1 or 3. If omitted or <= 0, we use the channel count of the
image on disk
RETURNED VALUE
A numpy array containing the pixel data
- mapping_file_framenocameraindex(*files_per_camera)
- Parse image filenames to get the frame numbers
SYNOPSIS
mapping = \
mapping_file_framenocameraindex( ('img5-cam2.jpg', 'img6-cam2.jpg'),
('img6-cam3.jpg', 'img7-cam3.jpg'),)
print(mapping)
===>
{ 'frame5-cam2.jpg': (5, 0),
'frame6-cam2.jpg': (6, 0),
'frame6-cam3.jpg': (6, 1),
'frame7-cam3.jpg': (7, 1) }
Prior to this call we already applied a glob to some images, so we already know
which images belong to which camera. This function further classifies the images
to find the frame number of each image. This is done by looking at the filenames
of images in each camera, removing common prefixes and suffixes, and using the
central varying filename component as the frame number. This varying component
should be numeric. If it isn't and we have multiple cameras, then we barf. If it
isn't, but we only have one camera, we fallback on sequential frame numbers.
If we have just one image for a camera, I can't tell what is constant in the
filenames, so I return framenumber=0.
ARGUMENTS
- *files_per_camera: one argument per camera. Each argument is a list of strings
of filenames of images observed by that camera
RETURNED VALUES
We return a dict from filenames to (framenumber, cameraindex) tuples. The
"cameraindex" is a sequential index counting up from 0. cameraindex==0
corresponds to files_per_camera[0] and so on.
The "framenumber" may not be sequential OR starting from 0: this comes directly
from the filename.
- match_feature(image0, image1, q0, *, search_radius1, template_size1, q1_estimate=None, H10=None, method=None, visualize=False, extratitle=None, return_plot_args=False, **kwargs)
- Find a pixel correspondence in a pair of images
SYNOPSIS
# Let's assume that the two cameras are roughly observing the plane defined
# by z=0 in the ref coordinate system. We also have an estimate of the
# camera extrinsics and intrinsics, so we can construct the homography that
# defines the relationship between the pixel observations in the vicinity of
# the q0 estimate. We use this homography to estimate the corresponding
# pixel coordinate q1, and we use it to transform the search template
def xy_from_q(model, q):
v, dv_dq, _ = mrcal.unproject(q, *model.intrinsics(),
get_gradients = True)
t_ref_cam = model.extrinsics_Rt_toref()[ 3,:]
R_ref_cam = model.extrinsics_Rt_toref()[:3,:]
vref = mrcal.rotate_point_R(R_ref_cam, v)
# We're looking at the plane z=0, so z = 0 = t_ref_cam[2] + k*vref[2]
k = -t_ref_cam[2]/vref[2]
xy = t_ref_cam[:2] + k*vref[:2]
H_xy_vref = np.array((( -t_ref_cam[2], 0, xy[0] - k*vref[0]),
( 0, -t_ref_cam[2], xy[1] - k*vref[1]),
( 0, 0, 1)))
H_v_q = nps.glue( dv_dq, nps.transpose(v - nps.inner(dv_dq,q)),
axis = -1)
H_xy_q = nps.matmult(H_xy_vref, R_ref_cam, H_v_q)
return xy, H_xy_q
xy, H_xy_q0 = xy_from_q(model0, q0)
v1 = mrcal.transform_point_Rt(model1.extrinsics_Rt_fromref(),
np.array((*xy, 0.)))
q1 = mrcal.project(v1, *model1.intrinsics())
_, H_xy_q1 = xy_from_q(model1, q1)
H10 = np.linalg.solve( H_xy_q1, H_xy_q0)
q1, diagnostics = \
mrcal.match_feature( image0, image1,
q0,
H10 = H10,
search_radius1 = 200,
template_size1 = 17 )
This function wraps the OpenCV cv2.matchTemplate() function to provide
additional functionality. The big differences are
1. The mrcal.match_feature() interface reports a matching pixel coordinate, NOT
a matching template. The conversions between templates and pixel coordinates
at their center are tedious and error-prone, and they're handled by this
function.
2. mrcal.match_feature() can take into account a homography that is applied to
the two images to match their appearance. The caller can estimate this from
the relative geometry of the two cameras and the geometry of the observed
object. If two pinhole cameras are observing a plane in space, a homography
exists to perfectly represent the observed images everywhere in view. The
homography can include a scaling (if the two cameras are looking at the same
object from different distances) and/or a rotation (if the two cameras are
oriented differently) and/or a skewing (if the object is being observed from
different angles)
3. mrcal.match_feature() performs simple sub-pixel interpolation to increase the
resolution of the reported pixel match
4. Visualization capabilities are included to allow the user to evaluate the
results
It is usually required to pre-filter the images being matched to get good
results. This function does not do this, and it is the caller's job to apply the
appropriate filters.
All inputs and outputs use the (x,y) convention normally utilized when talking
about images; NOT the (y,x) convention numpy uses to talk about matrices. So
template_size1 is specified as (width,height).
The H10 homography estimate is used in two separate ways:
1. To define the image transformation we apply to the template before matching
2. To compute the initial estimate of q1. This becomes the center of the search
window. We have
q1_estimate = mrcal.apply_homography(H10, q0)
A common use case is a translation-only homography. This avoids any image
transformation, but does select a q1_estimate. This special case is supported by
this function accepting a q1_estimate argument instead of H10. Equivalently, a
full translation-only homography may be passed in:
H10 = np.array((( 1., 0., q1_estimate[0]-q0[0]),
( 0., 1., q1_estimate[1]-q0[1]),
( 0., 0., 1.)))
The top-level logic of this function:
1. q1_estimate = mrcal.apply_homography(H10, q0)
2. Select a region in image1, centered at q1_estimate, with dimensions given in
template_size1
3. Transform this region to image0, using H10. The resulting transformed image
patch in image0 is used as the template
4. Select a region in image1, centered at q1_estimate, that fits the template
search_radius1 pixels off center in each dimension
4. cv2.matchTemplate() to search for the template in this region of image1
If the template being matched is out-of-bounds in either image, this function
raises an exception.
If the search_radius1 pushes the search outside of the search image, the search
bounds are reduced to fit into the given image, and the function works as
expected.
If the match fails in some data-dependent way, we return q1 = None instead of
raising an Exception. This can happen if the optimum cannot be found or if
subpixel interpolation fails.
if visualize: we produce a visualization of the best-fitting match. if not
return_plot_args: we display this visualization; else: we return the plot data,
so that we can create the plot later. The diagnostic plot contains 3 overlaid
images:
- The image being searched
- The homography-transformed template placed at the best-fitting location
- The correlation (or difference) image, placed at the best-fitting location
In an interactive gnuplotlib window, each image can be shown/hidden by clicking
on the relevant legend entry at the top-right of the image. Repeatedly toggling
the visibility of the template image is useful to communicate the fit accuracy.
The correlation image is guaranteed to appear at the end of plot_data_tuples, so
it can be omitted by plotting plot_data_tuples[:-1]. Skipping this image is
often most useful for quick human evaluation.
ARGUMENTS
- image0: the first image to use in the matching. This image is cropped, and
transformed using the H10 homography to produce the matching template. This is
interpreted as a grayscale image: 2-dimensional numpy array
- image1: the second image to use in the matching. This image is not
transformed, but cropped to accomodate the given template size and search
radius. We use this image as the base to compare the template against. The
same dimensionality, dtype logic applies as with image0
- q0: a numpy array of shape (2,) representing the pixel coordinate in image0
for which we seek a correspondence in image1
- search_radius1: integer selecting the search window size, in image1 pixels
- template_size1: an integer width or an iterable (width,height) describing the
size of the template used for matching. If an integer width is given, we use
(width,width). This is given in image1 coordinates, even though the template
itself comes from image0
- q1_estimate: optional numpy array of shape (2,) representing the pixel
coordinate in image1, which is our rough estimate for the camera1 observation
of the q0 observation in image0. If omitted, H10 specifies the initial
estimate. Exactly one of (q1_estimate,H10) must be given
- H10: optional numpy array of shape (3,3) containing the homography mapping q0
to q1 in the vicinity of the match. If omitted, we assume a translation-only
homography mapping q0 to q1_estimate. Exactly one of (q1_estimate,H10) must be
given
- method: optional constant, selecting the correlation function used in the
template comparison. If omitted or None, we default to normalized
cross-correlation: cv2.TM_CCORR_NORMED. For a description of available methods
see:
https://docs.opencv.org/master/df/dfb/group__imgproc__object.html
- visualize: optional boolean, defaulting to False. If True, we generate a plot
that describes the matching results. This overlays the search image, the
template, and the matching-output image, shifted to their optimized positions.
All 3 images are plotted direclty on top of one another. Clicking on the
legend in the resulting gnuplot window toggles that image on/off, which allows
the user to see how well things line up. if visualize and not
return_plot_args: we generate an interactive plot, and this function blocks
until the interactive plot is closed. if visualize and return_plot_args: we
generate the plot data and commands, but instead of creating the plot, we
return these data and commands, for the caller to post-process
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored. Used only if visualize
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
data_tuples, plot_options objects instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot. Used only if visualize
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc. Used only if visualize
RETURNED VALUES
We return a tuple:
- q1: a numpy array of shape (2,): the pixel coordinate in image1 corresponding
to the given q0. If the computation fails in some data-dependent way, this
value is None
- diagnostics: a dict containing diagnostics that describe the match. keys:
- matchoutput_image: the matchoutput array computed by cv2.matchTemplate()
- matchoutput_optimum_subpixel_at: the subpixel-refined coordinate of the
optimum in the matchoutput image
- matchoutput_optimum_subpixel: the value of the subpixel-refined optimum in the
matchoutput_image
- qshift_image1_matchoutput: the shift between matchoutput image coords and
image1 coords. We have
q1 = diagnostics['matchoutput_optimum_subpixel_at'] +
diagnostics['qshift_image1_matchoutput']
If visualize and return_plot_args: we return two more elements in the tuple:
data_tuples, plot_options. The plot can then be made with gp.plot(*data_tuples,
**plot_options).
- measurement_index_boards(...)
- Return the measurement index of the start of a given board observation
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
x = mrcal.optimizer_callback(**optimization_inputs)[1]
Nmeas = mrcal.num_measurements_boards ( **optimization_inputs)
i_meas0 = mrcal.measurement_index_boards(0, **optimization_inputs)
x_boards_all = x[i_meas0:i_meas0+Nmeas]
The optimization algorithm tries to minimize the norm of a "measurements" vector
x. The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.measurement_index_...() functions report where particular items end up in
the vector of measurements.
THIS function reports the index in the measurement vector where a particular
board observation begins. When solving calibration problems, most if not all of
the measurements will come from these observations. These are stored
contiguously.
In order to determine the layout, we need quite a bit of context. If we have
the full set of inputs to the optimization function, we can pass in those (as
shown in the example above). Or we can pass the individual arguments that are
needed (see ARGUMENTS section for the full list). If the optimization inputs and
explicitly-given arguments conflict about the size of some array, the explicit
arguments take precedence. If any array size is not specified, it is assumed to
be 0. Thus most arguments are optional.
ARGUMENTS
- i_observation_board: an integer indicating which board observation we're
querying
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_frames
do_optimize_calobject_warp
do_apply_regularization
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
Nobservations_point
calibration_object_width_n
calibration_object_height_n
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the variable index in the measurements vector where the
measurements for this particular board observation start
- measurement_index_points(...)
- Return the measurement index of the start of a given point observation
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
x = mrcal.optimizer_callback(**optimization_inputs)[1]
Nmeas = mrcal.num_measurements_points( **optimization_inputs)
i_meas0 = mrcal.measurement_index_points(0, **optimization_inputs)
x_points_all = x[i_meas0:i_meas0+Nmeas]
The optimization algorithm tries to minimize the norm of a "measurements" vector
x. The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.measurement_index_...() functions report where particular items end up in
the vector of measurements.
THIS function reports the index in the measurement vector where a particular
point observation begins. When solving structure-from-motion problems, most if
not all of the measurements will come from these observations. These are stored
contiguously.
In order to determine the layout, we need quite a bit of context. If we have the
full set of inputs to the optimization function, we can pass in those (as shown
in the example above). Or we can pass the individual arguments that are needed
(see ARGUMENTS section for the full list). If the optimization inputs and
explicitly-given arguments conflict about the size of some array, the explicit
arguments take precedence. If any array size is not specified, it is assumed to
be 0. Thus most arguments are optional.
ARGUMENTS
- i_observation_point: an integer indicating which point observation we're
querying
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_frames
do_optimize_calobject_warp
do_apply_regularization
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
Nobservations_point
calibration_object_width_n
calibration_object_height_n
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the variable index in the measurements vector where the
measurements for this particular point observation start
- measurement_index_regularization(...)
- Return the index of the start of the regularization measurements
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
x = mrcal.optimizer_callback(**optimization_inputs)[1]
Nmeas = mrcal.num_measurements_regularization( **optimization_inputs)
i_meas0 = mrcal.measurement_index_regularization(**optimization_inputs)
x_regularization = x[i_meas0:i_meas0+Nmeas]
The optimization algorithm tries to minimize the norm of a "measurements" vector
x. The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.measurement_index_...() functions report where particular items end up in
the vector of measurements.
THIS function reports the index in the measurement vector where the
regularization terms begin. These don't model physical effects, but guide the
solver away from obviously-incorrect solutions, and resolve ambiguities. This
helps the solver converge to the right solution, quickly.
In order to determine the layout, we need quite a bit of context. If we have the
full set of inputs to the optimization function, we can pass in those (as shown
in the example above). Or we can pass the individual arguments that are needed
(see ARGUMENTS section for the full list). If the optimization inputs and
explicitly-given arguments conflict about the size of some array, the explicit
arguments take precedence. If any array size is not specified, it is assumed to
be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_frames
do_optimize_calobject_warp
do_apply_regularization
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
Nobservations_point
calibration_object_width_n
calibration_object_height_n
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting where in the measurement vector the regularization terms
start
- num_intrinsics_optimization_params(...)
- Get the number of optimization parameters for a single camera's intrinsics
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
f( m.optimization_inputs() )
...
def f(optimization_inputs):
Nstates = mrcal.num_intrinsics_optimization_params(**optimization_inputs)
...
Return the number of parameters used in the optimization of the intrinsics of a
camera.
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what.
This function reports how many optimization parameters are used to represent the
intrinsics of a single camera. This is very similar to
mrcal.lensmodel_num_params(), except THIS function takes into account the
do_optimize_intrinsics_... variables used to lock down some parts of the
intrinsics vector. Similarly, we have mrcal.num_states_intrinsics(), which takes
into account the optimization details also, but reports the number of variables
needed to describe ALL the cameras instead of just one.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the number of optimization parameters used to describe the
intrinsics of a single camera
- num_measurements(...)
- Return how many measurements we have in the full optimization problem
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
x,J = mrcal.optimizer_callback(**optimization_inputs)[1:3]
Nmeas = mrcal.num_measurements(**optimization_inputs)
print(x.shape[0] - Nmeas)
===>
0
print(J.shape[0] - Nmeas)
===>
0
The optimization algorithm tries to minimize the norm of a "measurements" vector
x. The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.num_measurements_...() functions report where particular items end up in
the vector of measurements.
THIS function reports the total number of measurements we have. This corresponds
to the number of elements in the vector x and to the number of rows in the
jacobian matrix J.
In order to determine the mapping, we need quite a bit of context. If we have
the full set of inputs to the optimization function, we can pass in those (as
shown in the example above). Or we can pass the individual arguments that are
needed (see ARGUMENTS section for the full list). If the optimization inputs and
explicitly-given arguments conflict about the size of some array, the explicit
arguments take precedence. If any array size is not specified, it is assumed to
be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_frames
do_optimize_calobject_warp
do_apply_regularization
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
Nobservations_point
calibration_object_width_n
calibration_object_height_n
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the size of the measurement vector x
- num_measurements_boards(...)
- Return how many measurements we have from calibration object observations
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
x = mrcal.optimizer_callback(**optimization_inputs)[1]
Nmeas = mrcal.num_measurements_boards ( **optimization_inputs)
i_meas0 = mrcal.measurement_index_boards(0, **optimization_inputs)
x_boards_all = x[i_meas0:i_meas0+Nmeas]
The optimization algorithm tries to minimize the norm of a "measurements" vector
x. The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.num_measurements_...() functions report how many measurements are produced
by particular items.
THIS function reports how many measurements come from the observations of the
calibration object. When solving calibration problems, most if not all of the
measurements will come from these observations. These are stored contiguously.
In order to determine the layout, we need quite a bit of context. If we have
the full set of inputs to the optimization function, we can pass in those (as
shown in the example above). Or we can pass the individual arguments that are
needed (see ARGUMENTS section for the full list). If the optimization inputs and
explicitly-given arguments conflict about the size of some array, the explicit
arguments take precedence. If any array size is not specified, it is assumed to
be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_frames
do_optimize_calobject_warp
do_apply_regularization
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
Nobservations_point
calibration_object_width_n
calibration_object_height_n
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting how many elements of the measurement vector x come from
the calibration object observations
- num_measurements_points(...)
- Return how many measurements we have from point observations
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
x = mrcal.optimizer_callback(**optimization_inputs)[1]
Nmeas = mrcal.num_measurements_points( **optimization_inputs)
i_meas0 = mrcal.measurement_index_points(0, **optimization_inputs)
x_points_all = x[i_meas0:i_meas0+Nmeas]
The optimization algorithm tries to minimize the norm of a "measurements" vector
x. The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.num_measurements_...() functions report how many measurements are produced
by particular items.
THIS function reports how many measurements come from the observations of
discrete points. When solving structure-from-motion problems, most if not all of
the measurements will come from these observations. These are stored
contiguously.
In order to determine the layout, we need quite a bit of context. If we have the
full set of inputs to the optimization function, we can pass in those (as shown
in the example above). Or we can pass the individual arguments that are needed
(see ARGUMENTS section for the full list). If the optimization inputs and
explicitly-given arguments conflict about the size of some array, the explicit
arguments take precedence. If any array size is not specified, it is assumed to
be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_frames
do_optimize_calobject_warp
do_apply_regularization
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
Nobservations_point
calibration_object_width_n
calibration_object_height_n
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting how many elements of the measurement vector x come from
observations of discrete points
- num_measurements_regularization(...)
- Return how many measurements we have from regularization
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
x = mrcal.optimizer_callback(**optimization_inputs)[1]
Nmeas = mrcal.num_measurements_regularization( **optimization_inputs)
i_meas0 = mrcal.measurement_index_regularization(**optimization_inputs)
x_regularization = x[i_meas0:i_meas0+Nmeas]
The optimization algorithm tries to minimize the norm of a "measurements" vector
x. The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.num_measurements_...() functions report where particular items end up in
the vector of measurements.
THIS function reports how many measurements come from the regularization terms
of the optimization problem. These don't model physical effects, but guide the
solver away from obviously-incorrect solutions, and resolve ambiguities. This
helps the solver converge to the right solution, quickly.
In order to determine the layout, we need quite a bit of context. If we have the
full set of inputs to the optimization function, we can pass in those (as shown
in the example above). Or we can pass the individual arguments that are needed
(see ARGUMENTS section for the full list). If the optimization inputs and
explicitly-given arguments conflict about the size of some array, the explicit
arguments take precedence. If any array size is not specified, it is assumed to
be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_frames
do_optimize_calobject_warp
do_apply_regularization
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
Nobservations_point
calibration_object_width_n
calibration_object_height_n
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting how many elements of the measurement vector x come from
regularization terms
- num_states(...)
- Get the total number of parameters in the optimization vector
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
f( m.optimization_inputs() )
...
def f(optimization_inputs):
Nstates = mrcal.num_states (**optimization_inputs)
...
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.num_states_...() functions report how many variables in the optimization
vector are taken up by each particular kind of measurement.
THIS function reports how many variables are used to represent the FULL state
vector.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the total variable count in the state vector
- num_states_calobject_warp(...)
- Get the number of parameters in the optimization vector for the board warp
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b = mrcal.optimizer_callback(**optimization_inputs)[0]
mrcal.unpack_state(b, **optimization_inputs)
i_state0 = mrcal.state_index_calobject_warp(**optimization_inputs)
Nstates = mrcal.num_states_calobject_warp (**optimization_inputs)
calobject_warp = b[i_state0:i_state0+Nstates]
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.num_states_...() functions report how many variables in the optimization
vector are taken up by each particular kind of measurement.
THIS function reports how many variables are used to represent the
calibration-object warping. This is stored contiguously as in memory. These
warping parameters describe how the observed calibration object differs from the
expected calibration object. There will always be some difference due to
manufacturing tolerances and temperature and humidity effects.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the variable count of the calibration object warping
parameters
- num_states_extrinsics(...)
- Get the number of extrinsics parameters in the optimization vector
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b = mrcal.optimizer_callback(**optimization_inputs)[0]
mrcal.unpack_state(b, **optimization_inputs)
i_state0 = mrcal.state_index_extrinsics(0, **optimization_inputs)
Nstates = mrcal.num_states_extrinsics ( **optimization_inputs)
extrinsics_rt_fromref_all = b[i_state0:i_state0+Nstates]
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.num_states_...() functions report how many variables in the optimization
vector are taken up by each particular kind of measurement.
THIS function reports how many variables are used to represent ALL the camera
extrinsics. The extrinsics are stored contiguously as an "rt transformation": a
3-element rotation represented as a Rodrigues vector followed by a 3-element
translation. These transform points represented in the reference coordinate
system to the coordinate system of the specific camera. Note that mrcal allows
the reference coordinate system to be tied to a particular camera. In this case
the extrinsics of that camera do not appear in the state vector at all, and
icam_extrinsics == -1 in the indices_frame_camintrinsics_camextrinsics
array.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the variable count of extrinsics in the state vector
- num_states_frames(...)
- Get the number of calibration object pose parameters in the optimization vector
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b = mrcal.optimizer_callback(**optimization_inputs)[0]
mrcal.unpack_state(b, **optimization_inputs)
i_state0 = mrcal.state_index_frames(0, **optimization_inputs)
Nstates = mrcal.num_states_frames ( **optimization_inputs)
frames_rt_toref_all = b[i_state0:i_state0+Nstates]
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.num_states_...() functions report how many variables in the optimization
vector are taken up by each particular kind of measurement.
THIS function reports how many variables are used to represent ALL the frame
poses. Here a "frame" is a pose of the observed calibration object at some
instant in time. The frames are stored contiguously as an "rt transformation": a
3-element rotation represented as a Rodrigues vector followed by a 3-element
translation. These transform points represented in the internal calibration
object coordinate system to the reference coordinate system.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the variable count of frames in the state vector
- num_states_intrinsics(...)
- Get the number of intrinsics parameters in the optimization vector
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b = mrcal.optimizer_callback(**optimization_inputs)[0]
mrcal.unpack_state(b, **optimization_inputs)
i_state0 = mrcal.state_index_intrinsics(0, **optimization_inputs)
Nstates = mrcal.num_states_intrinsics ( **optimization_inputs)
intrinsics_all = b[i_state0:i_state0+Nstates]
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.num_states_...() functions report how many variables in the optimization
vector are taken up by each particular kind of measurement.
THIS function reports how many optimization variables are used to represent ALL
the camera intrinsics. The intrinsics are stored contiguously. They consist of a
4-element "intrinsics core" (focallength-x, focallength-y, centerpixel-x,
centerpixel-y) followed by a lensmodel-specific vector of "distortions". A
similar function mrcal.num_intrinsics_optimization_params() is available to
report the number of optimization variables used for just ONE camera. If all the
intrinsics are being optimized, then the mrcal.lensmodel_num_params() returns
the same value: the number of values needed to describe the intrinsics of a
single camera. It is possible to lock down some of the intrinsics during
optimization (by setting the do_optimize_intrinsics_... variables
appropriately). These variables control what
mrcal.num_intrinsics_optimization_params() and mrcal.num_states_intrinsics()
return, but not mrcal.lensmodel_num_params().
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the variable count of intrinsics in the state vector
- num_states_points(...)
- Get the number of point-position parameters in the optimization vector
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b = mrcal.optimizer_callback(**optimization_inputs)[0]
mrcal.unpack_state(b, **optimization_inputs)
i_state0 = mrcal.state_index_points(0, **optimization_inputs)
Nstates = mrcal.num_states_points ( **optimization_inputs)
points_all = b[i_state0:i_state0+Nstates]
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.num_states_...() functions report how many variables in the optimization
vector are taken up by each particular kind of measurement.
THIS function reports how many variables are used to represent ALL the points.
The points are stored contiguously as a 3-element coordinates in the reference
frame.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the variable count of points in the state vector
- optimize(...)
- Invoke the calibration routine
SYNOPSIS
stats = mrcal.optimize( intrinsics_data,
extrinsics_rt_fromref,
frames_rt_toref, points,
observations_board, indices_frame_camintrinsics_camextrinsics,
observations_point, indices_point_camintrinsics_camextrinsics,
lensmodel,
imagersizes = imagersizes,
do_optimize_intrinsics_core = True,
do_optimize_intrinsics_distortions= True,
calibration_object_spacing = object_spacing,
point_min_range = 0.1,
point_max_range = 100.0,
do_apply_outlier_rejection = True,
do_apply_regularization = True,
verbose = False)
Please see the mrcal documentation at
http://mrcal.secretsauce.net/formulation.html for details.
This is a flexible implementation of a calibration system core that uses sparse
Jacobians, performs outlier rejection and reports some metrics back to the user.
Measurements from any number of cameras can beat used simultaneously, and this
routine is flexible-enough to solve structure-from-motion problems.
The input is a combination of observations of a calibration board and
observations of discrete points. The point observations MAY have a known
range.
The cameras and what they're observing is given in the arrays
- intrinsics_data
- extrinsics_rt_fromref
- frames_rt_toref
- points
- indices_frame_camintrinsics_camextrinsics
- indices_point_camintrinsics_camextrinsics
intrinsics_data contains the intrinsics for all the physical cameras present in
the problem. len(intrinsics_data) = Ncameras_intrinsics
extrinsics_rt_fromref contains all the camera poses present in the problem,
omitting any cameras that sit at the reference coordinate system.
len(extrinsics_rt_fromref) = Ncameras_extrinsics.
frames_rt_toref is all the poses of the calibration board in the problem, and
points is all the discrete points being observed in the problem.
indices_frame_camintrinsics_camextrinsics describes which board observations
were made by which camera, and where this camera was. Each board observation is
described by a tuple (iframe,icam_intrinsics,icam_extrinsics). The board at
frames_rt_toref[iframe] was observed by camera
intrinsics_data[icam_intrinsics], which was at
extrinsics_rt_fromref[icam_extrinsics]
indices_point_camintrinsics_camextrinsics is the same thing for discrete points.
If we're solving a vanilla calibration problem, we have stationary cameras
observing a moving target. By convention, camera 0 is at the reference
coordinate system. So
- Ncameras_intrinsics = Ncameras_extrinsics+1
- All entries in indices_frame_camintrinsics_camextrinsics have
icam_intrinsics = icam_extrinsics+1
- frames_rt_toref, points describes the motion of the moving target we're
observing
Conversely, in a structure-from-motion problem we have some small number of
moving cameras (often just 1) observing stationary target(s). We would have
- Ncameras_intrinsics is small: it's how many physical cameras we have
- Ncameras_extrinsics is large: it describes the motion of the cameras
- frames_rt_toref, points is small: it describes the non-moving world we're
observing
Any combination of these extreme cases is allowed.
REQUIRED ARGUMENTS
- intrinsics: array of dims (Ncameras_intrinsics, Nintrinsics). The intrinsics
of each physical camera. Each intrinsic vector is given as
(focal_x, focal_y, center_pixel_x, center_pixel_y, distortion0, distortion1,
...)
The focal lengths are given in pixels.
On input this is a seed. On output the optimal data is returned. THIS ARRAY IS
MODIFIED BY THIS CALL.
- extrinsics_rt_fromref: array of dims (Ncameras_extrinsics, 6). The pose of
each camera observation. Each pose is given as 6 values: a Rodrigues rotation
vector followed by a translation. This represents a transformation FROM the
reference coord system TO the coord system of each camera.
On input this is a seed. On output the optimal data is returned. THIS ARRAY IS
MODIFIED BY THIS CALL.
If we only have one camera, pass either None or np.zeros((0,6))
- frames_rt_toref: array of dims (Nframes, 6). The poses of the calibration
object over time. Each pose is given as 6 values: a rodrigues rotation vector
followed by a translation. This represents a transformation FROM the coord
system of the calibration object TO the reference coord system. THIS IS
DIFFERENT FROM THE CAMERA EXTRINSICS.
On input this is a seed. On output the optimal data is returned. THIS ARRAY IS
MODIFIED BY THIS CALL.
If we don't have any frames, pass either None or np.zeros((0,6))
- points: array of dims (Npoints, 3). The estimated positions of discrete points
we're observing. These positions are represented in the reference coord
system. The initial Npoints-Npoints_fixed points are optimized by this
routine. The final Npoints_fixed points are fixed. By default
Npoints_fixed==0, and we optimize all the points.
On input this is a seed. On output the optimal data is returned. THIS ARRAY IS
MODIFIED BY THIS CALL.
- observations_board: array of dims (Nobservations_board,
calibration_object_height_n,
calibration_object_width_n,
3).
Each slice is an (x,y,weight) tuple where (x,y) are the observed pixel
coordinates of the corners in the calibration object, and "weight" is the
relative weight of this point observation. Most of the weights are expected to
be 1.0, which implies that the noise on that observation has the nominal
standard deviation of observed_pixel_uncertainty (in addition to the overall
assumption of gaussian noise, independent on x,y). weight<0 indicates that
this is an outlier. This is respected on input (even if
!do_apply_outlier_rejection). New outliers are marked with weight<0 on output.
Subpixel interpolation is assumed, so these contain 64-bit floating point
values, like all the other data. The frame and camera that produced these
observations are given in the indices_frame_camintrinsics_camextrinsics
THIS ARRAY IS MODIFIED BY THIS CALL (to mark outliers)
- indices_frame_camintrinsics_camextrinsics: array of dims (Nobservations_board,
3). For each observation these are an
(iframe,icam_intrinsics,icam_extrinsics) tuple. icam_extrinsics == -1
means this observation came from a camera in the reference coordinate system.
iframe indexes the "frames_rt_toref" array, icam_intrinsics indexes the
"intrinsics_data" array, icam_extrinsics indexes the "extrinsics_rt_fromref"
array
All of the indices are guaranteed to be monotonic. This array contains 32-bit
integers.
- observations_point: array of dims (Nobservations_point, 3). Each slice is an
(x,y,weight) tuple where (x,y) are the pixel coordinates of the observed
point, and "weight" is the relative weight of this point observation. Most of
the weights are expected to be 1.0, which implies that the noise on the
observation is gaussian, independent on x,y, and has the nominal standard
deviation of observed_pixel_uncertainty. weight<0 indicates that this is an
outlier. This is respected on input (even if !do_apply_outlier_rejection). At
this time, no new outliers are detected for point observations. Subpixel
interpolation is assumed, so these contain 64-bit floating point values, like
all the other data. The point index and camera that produced these
observations are given in the indices_point_camera_points array.
- indices_point_camintrinsics_camextrinsics: array of dims (Nobservations_point,
3). For each observation these are an
(i_point,icam_intrinsics,icam_extrinsics) tuple. Analogous to
indices_frame_camintrinsics_camextrinsics, but for observations of discrete
points.
The indices can appear in any order. No monotonicity is required. This array
contains 32-bit integers.
- lensmodel: a string such as
LENSMODEL_PINHOLE
LENSMODEL_OPENCV4
LENSMODEL_CAHVOR
LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=12_fov_x_deg=100
LENSMODEL_CAHVORE is explicitly NOT supported at this time since gradients are
required
- imagersizes: integer array of dims (Ncameras_intrinsics,2)
OPTIONAL ARGUMENTS
- calobject_warp
A numpy array of shape (2,) describing the non-flatness of the calibration
board. If omitted or None, the board is assumed to be perfectly flat. And if
do_optimize_calobject_warp then we optimize these parameters to find the
best-fitting board shape.
- Npoints_fixed
Specifies how many points at the end of the points array are fixed, and remain
unaffected by the optimization. This is 0 by default, and we optimize all the
points.
- do_optimize_intrinsics_core
- do_optimize_intrinsics_distortions
- do_optimize_extrinsics
- do_optimize_frames
- do_optimize_calobject_warp
Indicate whether to optimize a specific set of variables. The intrinsics core
is fx,fy,cx,cy. These all default to True so if we specify none of these, we
will optimize ALL the variables.
- calibration_object_spacing: the width of each square in a calibration board.
Can be omitted if we have no board observations, just points. The calibration
object has shape (calibration_object_height_n,calibration_object_width_n),
given by the dimensions of "observations_board"
- verbose: if True, write out all sorts of diagnostic data to STDERR. Defaults
to False
- do_apply_outlier_rejection: if False, don't bother with detecting or rejecting
outliers. The outliers we get on input (observations_board[...,2] < 0) are
honered regardless. Defaults to True
- do_apply_regularization: if False, don't include regularization terms in the
solver. Defaults to True
- point_min_range, point_max_range: Required ONLY if point observations are
given. These are lower, upper bounds for the distance of a point observation
to its observing camera. Each observation outside of this range is penalized.
This helps the solver by guiding it away from unreasonable solutions.
We return a dict with various metrics describing the computation we just
performed
- optimizer_callback(...)
- Call the optimization callback function
SYNOPSIS
model = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = model.optimization_inputs()
b_packed,x,J_packed,factorization = \
mrcal.optimizer_callback( **optimization_inputs )
Please see the mrcal documentation at
http://mrcal.secretsauce.net/formulation.html for details.
The main optimization routine in mrcal.optimize() searches for optimal
parameters by repeatedly calling a function to evaluate each hypothethical
parameter set. This evaluation function is available by itself here, separated
from the optimization loop. The arguments are largely the same as those to
mrcal.optimize(), but the inputs are all read-only. Some arguments that have
meaning in calls to optimize() have no meaning in calls to optimizer_callback().
These are accepted, and effectively ignored. Currently these are:
- do_apply_outlier_rejection
ARGUMENTS
This function accepts lots of arguments, but they're the same as the arguments
to mrcal.optimize() so please see that documentation for details. Arguments
accepted by optimizer_callback() on top of those in optimize():
- no_jacobian: optional boolean defaulting to False. If True, we do not compute
a jacobian, which would speed up this function. We then return None in its
place. if no_jacobian and not no_factorization then we still compute and
return a jacobian, since it's needed for the factorization
- no_factorization: optional boolean defaulting to False. If True, we do not
compute a cholesky factorization of JtJ, which would speed up this function.
We then return None in its place. if no_jacobian and not no_factorization then
we still compute and return a jacobian, since it's needed for the
factorization
RETURNED VALUES
The output is returned in a tuple:
- b_packed: a numpy array of shape (Nstate,). This is the packed (unitless)
state vector that represents the inputs, as seen by the optimizer. If the
optimization routine was running, it would use this as a starting point in the
search for different parameters, trying to find those that minimize norm2(x).
This packed state can be converted to the expanded representation like this:
b = mrcal.optimizer_callback(**optimization_inputs)[0
mrcal.unpack_state(b, **optimization_inputs)
- x: a numpy array of shape (Nmeasurements,). This is the error vector. If the
optimization routine was running, it would be testing different parameters,
trying to find those that minimize norm2(x)
- J: a sparse matrix of shape (Nmeasurements,Nstate). These are the gradients of
the measurements in respect to the packed parameters. This is a SPARSE array
of type scipy.sparse.csr_matrix. This object can be converted to a numpy array
like this:
b,x,J_sparse = mrcal.optimizer_callback(...)[:3]
J_numpy = J_sparse.toarray()
Note that the numpy array is dense, so it is very inefficient for sparse data,
and working with it could be very memory-intensive and slow.
This jacobian matrix comes directly from the optimization callback function,
which uses packed, unitless state. To convert a densified packed jacobian to
full units, one can do this:
J_sparse = mrcal.optimizer_callback(**optimization_inputs)[2]
J_numpy = J_sparse.toarray()
mrcal.pack_state(J_numpy, **optimization_inputs)
Note that we're calling pack_state() instead of unpack_state() because the
packed variables are in the denominator
- factorization: a Cholesky factorization of JtJ in a
mrcal.CHOLMOD_factorization object. The core of the optimization algorithm is
solving a linear system JtJ x = b. J is a large, sparse matrix, so we do this
with a Cholesky factorization of J using the CHOLMOD library. This
factorization is also useful in other contexts, such as uncertainty
quantification, so we make it available here. If the factorization could not
be computed (because JtJ isn't full-rank for instance), this is set to None
- pack_state(...)
- Scales a state vector to the packed, unitless form used by the optimizer
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
Jpacked = mrcal.optimizer_callback(**optimization_inputs)[2].toarray()
J = Jpacked.copy()
mrcal.pack_state(J, **optimization_inputs)
In order to make the optimization well-behaved, we scale all the variables in
the state and the gradients before passing them to the optimizer. The internal
optimization library thus works only with unitless (or "packed") data.
This function takes a full numpy array of shape (...., Nstate), and scales it to
produce packed data. This function applies the scaling directly to the input
array; the input is modified, and nothing is returned.
To unpack a state vector, you naturally call unpack_state(). To unpack a
jacobian matrix, you would call pack_state() because in a jacobian, the state is
in the denominator. This is shown in the example above.
Broadcasting is supported: any leading dimensions will be processed correctly,
as long as the given array has shape (..., Nstate).
In order to know what the scale factors should be, and how they should map to
each variable in the state vector, we need quite a bit of context. If we have
the full set of inputs to the optimization function, we can pass in those (as
shown in the example above). Or we can pass the individual arguments that are
needed (see ARGUMENTS section for the full list). If the optimization inputs and
explicitly-given arguments conflict about the size of some array, the explicit
arguments take precedence. If any array size is not specified, it is assumed to
be 0. Thus most arguments are optional.
ARGUMENTS
- b: a numpy array of shape (..., Nstate). This is the full state on input, and
the packed state on output. The input array is modified.
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
None. The scaling is applied to the input array
- pinhole_model_for_reprojection(model_from, fit=None, *, scale_focal=None, scale_image=None)
- Generate a pinhole model suitable for reprojecting an image
SYNOPSIS
model_orig = mrcal.cameramodel("xxx.cameramodel")
image_orig = mrcal.load_image("image.jpg")
model_pinhole = mrcal.pinhole_model_for_reprojection(model_orig,
fit = "corners")
mapxy = mrcal.image_transformation_map(model_orig, model_pinhole,
intrinsics_only = True)
image_undistorted = mrcal.transform_image(image_orig, mapxy)
Many algorithms work with images assumed to have been captured with a pinhole
camera, even though real-world lenses never fit a pinhole model. mrcal provides
several functions to remap images captured with non-pinhole lenses into images
of the same scene as if they were observed by a pinhole lens. When doing this,
we're free to choose all of the parameters of this pinhole lens model. THIS
function produces the pinhole camera model based on some guidance in the
arguments, and this model can then be used to "undistort" images.
ARGUMENTS
- model_from: the mrcal.cameramodel object used to build the pinhole model. We
use the intrinsics as the baseline, and we copy the extrinsics to the
resulting pinhole model.
- fit: optional specification for focal-length scaling. By default we use the
focal length values from the input model. This is either a numpy array of
shape (...,2) containing pixel coordinates that the resulting pinhole model
must represent, or one of ("corners","centers-horizontal","centers-vertical").
See the docstring for scale_focal__best_pinhole_fit() for details. Exclusive
with 'scale_focal'
- scale_focal: optional specification for focal-length scaling. By default we
use the focal length values from the input model. If given, we scale the input
focal lengths by the given value. Exclusive with 'fit'
- scale_image: optional specification for the scaling of the image size. By
default the output model represents an image of the same resolution as the
input model. If we want something else, the scaling can be given here.
RETURNED VALUE
A mrcal.cameramodel object with lensmodel = LENSMODEL_PINHOLE corresponding to
the input model.
- plotoptions_measurement_boundaries(**optimization_inputs)
- Return the 'set' plot options for gnuplotlib to show the measurement boundaries
SYNOPSIS
import numpy as np
import gnuplotlib as gp
import mrcal
model = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = model.optimization_inputs()
x = mrcal.optimizer_callback(**optimization_inputs)[1]
gp.plot( np.abs(x),
_set = mrcal.plotoptions_measurement_boundaries(**optimization_inputs) )
# a plot pops up showing the magnitude of each measurement, with boundaries
# between the different measurements denoted
When plotting the measurement vector (or anything relating to it, such as
columns of the Jacobian), it is usually very useful to infer at a glance the
meaning of each part of the plot. This function returns a list of 'set'
directives passable to gnuplotlib that show the boundaries inside the
measurement vector.
ARGUMENTS
**optimization_inputs: a dict() of arguments passable to mrcal.optimize() and
mrcal.optimizer_callback(). These define the full optimization problem, and can
be obtained from the optimization_inputs() method of mrcal.cameramodel
RETURNED VALUE
A list of 'set' directives passable as plot options to gnuplotlib
- plotoptions_state_boundaries(**optimization_inputs)
- Return the 'set' plot options for gnuplotlib to show the state boundaries
SYNOPSIS
import numpy as np
import gnuplotlib as gp
import mrcal
model = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = model.optimization_inputs()
J = mrcal.optimizer_callback(**optimization_inputs)[2]
gp.plot( np.sum(np.abs(J.toarray()), axis=-2),
_set = mrcal.plotoptions_state_boundaries(**optimization_inputs) )
# a plot pops up showing the magnitude of the effects of each element of the
# packed state (as seen by the optimizer), with boundaries between the
# different state variables denoted
When plotting the state vector (or anything relating to it, such as rows of the
Jacobian), it is usually very useful to infer at a glance the meaning of each
part of the plot. This function returns a list of 'set' directives passable to
gnuplotlib that show the boundaries inside the state vector.
ARGUMENTS
**optimization_inputs: a dict() of arguments passable to mrcal.optimize() and
mrcal.optimizer_callback(). These define the full optimization problem, and can
be obtained from the optimization_inputs() method of mrcal.cameramodel
RETURNED VALUE
A list of 'set' directives passable as plot options to gnuplotlib
- polygon_difference(positive, negative)
- Return the difference of two closed polygons
SYNOPSIS
import numpy as np
import numpysane as nps
import gnuplotlib as gp
A = np.array(((-1,-1),( 1,-1),( 1, 1),(-1, 1),(-1,-1)))
B = np.array(((-.1,-1.1),( .1,-1.1),( .1, 1.1),(-.1, 1.1),(-.1,-1.1)))
diff = mrcal.polygon_difference(A, B)
gp.plot( (A, dict(legend = 'A', _with = 'lines')),
(B, dict(legend = 'B', _with = 'lines')),
*[ ( r, dict( _with = 'filledcurves closed fillcolor "red"',
legend = 'difference'))
for r in diff],
tuplesize = -2,
square = True,
wait = True)
Given two polygons specified as a point sequence in arrays of shape (N,2) this
function computes the topological difference: all the regions contained in the
positive polygon, but missing in the negative polygon. The result could be
empty, or it could contain any number of disconnected polygons, so a list of
polygons is returned. Each of the constituent resulting polygons is guaranteed
to not have holes. If any holes are found when computing the difference, we cut
apart the resulting shape until no holes remain.
ARGUMENTS
- positive: a polygon specified by a sequence of points in an array of shape
(N,2). The resulting difference describes regions contained inside the
positive polygon
- negative: a polygon specified by a sequence of points in an array of shape
(N,2). The resulting difference describes regions outside the negative polygon
RETURNED VALUE
A list of arrays of shape (N,2). Each array in the list describes a hole-free
polygon as a sequence of points. The difference is a union of all these
constituent polygons. This list could have 0 elements (empty difference) or N
element (difference consists of N separate polygons)
- project(v, lensmodel, intrinsics_data, *, get_gradients=False, out=None)
- Projects a set of 3D camera-frame points to the imager
SYNOPSIS
# v is a (...,3) array of 3D points we're projecting
points = mrcal.project( v,
lensmodel, intrinsics_data )
### OR ###
m = mrcal.cameramodel(...)
points = mrcal.project( v, *m.intrinsics() )
# points is a (...,2) array of pixel coordinates
Given a shape-(...,3) array of points in the camera frame (x,y aligned with the
imager coords, z 'forward') and an intrinsic model, this function computes the
projection, optionally with gradients.
Projecting out-of-bounds points (beyond the field of view) returns undefined
values. Generally things remain continuous even as we move off the imager
domain. Pinhole-like projections will work normally if projecting a point behind
the camera. Splined projections clamp to the nearest spline segment: the
projection will fly off to infinity quickly since we're extrapolating a
polynomial, but the function will remain continuous.
Broadcasting is fully supported across v and intrinsics_data
ARGUMENTS
- points: array of dims (...,3); the points we're projecting
- lensmodel: a string such as
LENSMODEL_PINHOLE
LENSMODEL_OPENCV4
LENSMODEL_CAHVOR
LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=12_fov_x_deg=100
- intrinsics: array of dims (Nintrinsics):
(focal_x, focal_y, center_pixel_x, center_pixel_y, distortion0, distortion1,
...)
The focal lengths are given in pixels.
- get_gradients: optional boolean that defaults to False. Whether we should
compute and report the gradients. This affects what we return
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing arrays,
specify them with the 'out' kwarg. If not get_gradients: 'out' is the one
numpy array we will write into. Else: 'out' is a tuple of all the output numpy
arrays. If 'out' is given, we return the same arrays passed in. This is the
standard behavior provided by numpysane_pywrap.
RETURNED VALUE
if not get_gradients:
we return an (...,2) array of projected pixel coordinates
if get_gradients: we return a tuple:
- (...,2) array of projected pixel coordinates
- (...,2,3) array of gradients of the pixel coordinates in respect to the
input 3D point positions
- (...,2,Nintrinsics) array of the gradients of the pixel coordinates in
respect to the intrinsics
- project_latlon(points, fxycxy=array([1., 1., 0., 0.]), *, get_gradients=False, out=None)
- Projects 3D camera-frame points using a transverse equirectangular projection
SYNOPSIS
# points is a (N,3) array of camera-coordinate-system points
q = mrcal.project_latlon( points, fxycxy )
# q is now a (N,2) array of transverse equirectangular coordinates
This is a special case of mrcal.project(). Useful not for representing lenses,
but for performing stereo rectification. Lenses do not follow this model. See
the lensmodel documentation for details:
http://mrcal.secretsauce.net/lensmodels.html#lensmodel-latlon
Given a (N,3) array of points in the camera frame (x,y aligned with the imager
coords, z 'forward') and the parameters fxycxy, this function computes the
projection, optionally with gradients.
ARGUMENTS
- points: array of dims (...,3); the points we're projecting. This supports
broadcasting fully, and any leading dimensions are allowed, including none
- fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy). fx
and fy are the "focal lengths": they specify the angular resolution of the
image, in pixels/radian. (cx,cy) are pixel coordinates corresponding to the
projection of p = [0,0,1]. If omitted, default values are used to specify a
normalized transverse equirectangular projection : fx=fy=1.0 and cx=cy=0.0.
This produces q = (lat,lon)
- get_gradients: optional boolean, defaults to False. This affects what we
return (see below)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing arrays,
specify them with the 'out' kwarg. If not get_gradients: 'out' is the one
numpy array we will write into. Else: 'out' is a tuple of all the output numpy
arrays. If 'out' is given, we return the same arrays passed in. This is the
standard behavior provided by numpysane_pywrap.
RETURNED VALUE
if not get_gradients: we return an (...,2) array of projected transverse
equirectangular coordinates
if get_gradients: we return a tuple:
- (...,2) array of projected transverse equirectangular coordinates
- (...,2,3) array of the gradients of the transverse equirectangular
coordinates in respect to the input 3D point positions
- project_lonlat(points, fxycxy=array([1., 1., 0., 0.]), *, get_gradients=False, out=None)
- Projects a set of 3D camera-frame points using an equirectangular projection
SYNOPSIS
# points is a (N,3) array of camera-coordinate-system points
q = mrcal.project_lonlat( points, fxycxy )
# q is now a (N,2) array of equirectangular coordinates
This is a special case of mrcal.project(). Useful not for
representing lenses, but for describing the projection function of wide
panoramic images. Lenses do not follow this model. See the lensmodel
documentation for details:
http://mrcal.secretsauce.net/lensmodels.html#lensmodel-lonlat
Given a (N,3) array of points in the camera frame (x,y aligned with the imager
coords, z 'forward') and the parameters fxycxy, this function computes the
projection, optionally with gradients.
ARGUMENTS
- points: array of dims (...,3); the points we're projecting. This supports
broadcasting fully, and any leading dimensions are allowed, including none
- fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy). fx
and fy are the "focal lengths": they specify the angular resolution of the
image, in pixels/radian. (cx,cy) are pixel coordinates corresponding to the
projection of p = [0,0,1]. If omitted, default values are used to specify a
normalized equirectangular projection : fx=fy=1.0 and cx=cy=0.0. This produces
q = (lon,lat)
- get_gradients: optional boolean, defaults to False. This affects what we
return (see below)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing arrays,
specify them with the 'out' kwarg. If not get_gradients: 'out' is the one
numpy array we will write into. Else: 'out' is a tuple of all the output numpy
arrays. If 'out' is given, we return the same arrays passed in. This is the
standard behavior provided by numpysane_pywrap.
RETURNED VALUE
if not get_gradients: we return an (...,2) array of projected equirectangular
coordinates
if get_gradients: we return a tuple:
- (...,2) array of projected equirectangular coordinates
- (...,2,3) array of the gradients of the equirectangular coordinates in respect
to the input 3D point positions
- project_pinhole(points, fxycxy=array([1., 1., 0., 0.]), *, get_gradients=False, out=None)
- Projects 3D camera-frame points using a pinhole projection
SYNOPSIS
# points is a (N,3) array of camera-coordinate-system points
q = mrcal.project_pinhole( points, fxycxy )
# q is now a (N,2) array of pinhole coordinates
This is a special case of mrcal.project(). Useful to represent a very simple,
very perfect lens. Wide lenses do not follow this model. Long lenses usually
more-or-less DO follow this model. See the lensmodel documentation for details:
http://mrcal.secretsauce.net/lensmodels.html#lensmodel-pinhole
Given a (N,3) array of points in the camera frame (x,y aligned with the imager
coords, z 'forward') and the parameters fxycxy, this function computes the
projection, optionally with gradients.
ARGUMENTS
- points: array of dims (...,3); the points we're projecting. This supports
broadcasting fully, and any leading dimensions are allowed, including none
- fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy),
with all elements given in units of pixels. fx and fy are the horizontal and
vertical focal lengths, respectively. (cx,cy) are pixel coordinates
corresponding to the projection of p = [0,0,1]. If omitted, default values are
used: fx=fy=1.0 and cx=cy=0.0.
- get_gradients: optional boolean, defaults to False. This affects what we
return (see below)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing arrays,
specify them with the 'out' kwarg. If not get_gradients: 'out' is the one
numpy array we will write into. Else: 'out' is a tuple of all the output numpy
arrays. If 'out' is given, we return the same arrays passed in. This is the
standard behavior provided by numpysane_pywrap.
RETURNED VALUE
if not get_gradients: we return an (...,2) array of projected transverse
equirectangular coordinates
if get_gradients: we return a tuple:
- (...,2) array of projected pinhole coordinates
- (...,2,3) array of the gradients of the transverse equirectangular
coordinates in respect to the input 3D point positions
- project_stereographic(points, fxycxy=array([1., 1., 0., 0.]), *, get_gradients=False, out=None)
- Projects a set of 3D camera-frame points using a stereographic model
SYNOPSIS
# points is a (N,3) array of camera-coordinate-system points
q = mrcal.project_stereographic( points )
# q is now a (N,2) array of normalized stereographic coordinates
This is a special case of mrcal.project(). No actual lens ever follows this
model exactly, but this is useful as a baseline for other models. See the
lensmodel documentation for details:
http://mrcal.secretsauce.net/lensmodels.html#lensmodel-stereographic
Given a (N,3) array of points in the camera frame (x,y aligned with the imager
coords, z 'forward') and parameters of a perfect stereographic camera, this
function computes the projection, optionally with gradients.
The user can pass in focal length and center-pixel values. Or they can be
omitted to compute a "normalized" stereographic projection (fx = fy = 1, cx = cy
= 0).
The stereographic projection is able to represent points behind the camera, and
has only one singular observation direction: directly behind the camera, along
the optical axis.
This projection acts radially. If the observation vector v makes an angle theta
with the optical axis, then the projected point q is 2 tan(theta/2) f from the
image center.
ARGUMENTS
- points: array of dims (...,3); the points we're projecting. This supports
broadcasting fully, and any leading dimensions are allowed, including none
- fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy),
with all elements given in units of pixels. fx and fy are the horizontal and
vertical focal lengths, respectively. (cx,cy) are pixel coordinates
corresponding to the projection of p = [0,0,1]. If omitted, default values are
used to specify a normalized stereographic projection : fx=fy=1.0 and
cx=cy=0.0.
- get_gradients: optional boolean, defaults to False. This affects what we
return (see below)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing arrays,
specify them with the 'out' kwarg. If not get_gradients: 'out' is the one
numpy array we will write into. Else: 'out' is a tuple of all the output numpy
arrays. If 'out' is given, we return the same arrays passed in. This is the
standard behavior provided by numpysane_pywrap.
RETURNED VALUE
if not get_gradients: we return an (...,2) array of projected stereographic
coordinates
if get_gradients: we return a tuple:
- (...,2) array of projected stereographic coordinates
- (...,2,3) array of the gradients of the stereographic coordinates in respect
to the input 3D point positions
- projection_diff(models, *, implied_Rt10=None, gridn_width=60, gridn_height=None, intrinsics_only=False, distance=None, use_uncertainties=True, focus_center=None, focus_radius=-1.0)
- Compute the difference in projection between N models
SYNOPSIS
models = ( mrcal.cameramodel('cam0-dance0.cameramodel'),
mrcal.cameramodel('cam0-dance1.cameramodel') )
difference,_,q0,_ = mrcal.projection_diff(models)
print(q0.shape)
==> (40,60)
print(difference.shape)
==> (40,60)
# The differences are computed across a grid. 'q0' is the pixel centers of
# each grid cell. 'difference' is the projection variation between the two
# models at each cell
The operation of this tool is documented at
http://mrcal.secretsauce.net/differencing.html
It is often useful to compare the projection behavior of two camera models. For
instance, one may want to validate a calibration by comparing the results of two
different chessboard dances. Or one may want to evaluate the stability of the
intrinsics in response to mechanical or thermal stresses. This function makes
these comparisons, and returns the results. A visualization wrapper is
available: mrcal.show_projection_diff() and the mrcal-show-projection-diff tool.
In the most common case we're given exactly 2 models to compare, and we compute
the differences in projection of each point. If we're given more than 2 models,
we instead compute the standard deviation of the differences between models 1..N
and model0.
The top-level operation of this function:
- Grid the imager
- Unproject each point in the grid using one camera model
- Apply a transformation to map this point from one camera's coord system to the
other. How we obtain this transformation is described below
- Project the transformed points to the other camera
- Look at the resulting pixel difference in the reprojection
If implied_Rt10 is given, we simply use that as the transformation (this is
currently supported ONLY for diffing exactly 2 cameras). If implied_Rt10 is not
given, we estimate it. Several variables control this. Top-level logic:
if intrinsics_only:
Rt10 = identity_Rt()
else:
if focus_radius == 0:
Rt10 = relative_extrinsics(models)
else:
Rt10 = implied_Rt10__from_unprojections()
Sometimes we want to look at the intrinsics differences in isolation (if
intrinsics_only), and sometimes we want to use the known geometry in the given
models (not intrinsics_only and focus_radius == 0). If neither of these apply,
we estimate the transformation: this is needed if we're comparing different
calibration results from the same lens.
Given different camera models, we have a different set of intrinsics for each.
Extrinsics differ also, even if we're looking at different calibration of the
same stationary lens: the position and orientation of the camera coordinate
system in respect to the physical camera housing shift with each calibration.
This geometric variation is baked into the intrinsics. So when we project "the
same world point" into both cameras (as is desired when comparing repeated
calibrations), we must apply a geometric transformation because we want to be
comparing projections of world points (relative to the camera housing), not
projections relative to the (floating) camera coordinate systems. This
transformation is unknown, but we can estimate it by fitting projections across
the imager: the "right" transformation would result in apparent low projection
differences in a wide area.
This transformation is computed by implied_Rt10__from_unprojections(), and some
details of its operation are significant:
- The imager area we use for the fit
- Which world points we're looking at
In most practical usages, we would not expect a good fit everywhere in the
imager: areas where no chessboards were observed will not fit well, for
instance. From the point of view of the fit we perform, those ill-fitting areas
should be treated as outliers, and they should NOT be a part of the solve. How
do we specify the well-fitting area? The best way is to use the model
uncertainties: these can be used to emphasize the confident regions of the
imager. This behavior is selected with use_uncertainties=True, which is the
default. If uncertainties aren't available, or if we want a faster solve, pass
use_uncertainties=False. The well-fitting region can then be passed using the
focus_center,focus_radius arguments to indicate the circle in the imager we care
about.
If use_uncertainties then the defaults for focus_center,focus_radius are set to
utilize all the data in the imager. If not use_uncertainties, then the defaults
are to use a more reasonable circle of radius min(width,height)/6 at the center
of the imager. Usually this is sufficiently correct, and we don't need to mess
with it. If we aren't guided to the correct focus region, the
implied-by-the-intrinsics solve will try to fit lots of outliers, which would
result in an incorrect transformation, which in turn would produce overly-high
reported diffs. A common case when this happens is if the chessboard
observations used in the calibration were concentrated to the side of the image
(off-center), no uncertainties were used, and the focus_center was not pointed
to that area.
Unlike the projection operation, the diff operation is NOT invariant under
geometric scaling: if we look at the projection difference for two points at
different locations along a single observation ray, there will be a variation in
the observed diff. This is due to the geometric difference in the two cameras.
If the models differed only in their intrinsics parameters, then this variation
would not appear. Thus we need to know how far from the camera to look, and this
is specified by the "distance" argument. By default (distance = None) we look
out to infinity. If we care about the projection difference at some other
distance, pass that here. Multiple distances can be passed in an iterable. We'll
then fit the implied-by-the-intrinsics transformation using all the distances,
and we'll return the differences for each given distance. Generally the most
confident distance will be where the chessboards were observed at calibration
time.
ARGUMENTS
- models: iterable of mrcal.cameramodel objects we're comparing. Usually there
will be 2 of these, but more than 2 is allowed. The intrinsics are always
used; the extrinsics are used only if not intrinsics_only and focus_radius==0
- implied_Rt10: optional transformation to use to line up the camera coordinate
systems. Most of the time we want to estimate this transformation, so this
should be omitted or None. Currently this is supported only if exactly two
models are being compared.
- gridn_width: optional value, defaulting to 60. How many points along the
horizontal gridding dimension
- gridn_height: how many points along the vertical gridding dimension. If None,
we compute an integer gridn_height to maintain a square-ish grid:
gridn_height/gridn_width ~ imager_height/imager_width
- intrinsics_only: optional boolean, defaulting to False. If True: we evaluate
the intrinsics of each lens in isolation by assuming that the coordinate
systems of each camera line up exactly
- distance: optional value, defaulting to None. Has an effect only if not
intrinsics_only. The projection difference varies depending on the range to
the observed world points, with the queried range set in this 'distance'
argument. If None (the default) we look out to infinity. We can compute the
implied-by-the-intrinsics transformation off multiple distances if they're
given here as an iterable. This is especially useful if we have uncertainties,
since then we'll emphasize the best-fitting distances.
- use_uncertainties: optional boolean, defaulting to True. Used only if not
intrinsics_only and focus_radius!=0. If True we use the whole imager to fit
the implied-by-the-intrinsics transformation, using the uncertainties to
emphasize the confident regions. If False, it is important to select the
confident region using the focus_center and focus_radius arguments. If
use_uncertainties is True, but that data isn't available, we report a warning,
and try to proceed without.
- focus_center: optional array of shape (2,); the imager center by default. Used
only if not intrinsics_only and focus_radius!=0. Used to indicate that the
implied-by-the-intrinsics transformation should use only those pixels a
distance focus_radius from focus_center. This is intended to be used if no
uncertainties are available, and we need to manually select the focus region.
- focus_radius: optional value. If use_uncertainties then the default is LARGE,
to use the whole imager. Else the default is min(width,height)/6. Used to
indicate that the implied-by-the-intrinsics transformation should use only
those pixels a distance focus_radius from focus_center. This is intended to be
used if no uncertainties are available, and we need to manually select the
focus region. To avoid computing the transformation, either pass
focus_radius=0 (to use the extrinsics in the given models) or pass
intrinsics_only=True (to use the identity transform).
RETURNED VALUE
A tuple
- difflen: a numpy array of shape (...,gridn_height,gridn_width) containing the
magnitude of differences at each cell, or the standard deviation of the
differences between models 1..N and model0 if len(models)>2. if
len(models)==2: this is nps.mag(diff). If the given 'distance' argument was an
iterable, the shape is (len(distance),...). Otherwise the shape is (...)
- diff: a numpy array of shape (...,gridn_height,gridn_width,2) containing the
vector of differences at each cell. If len(models)>2 this isn't defined, so
None is returned. If the given 'distance' argument was an iterable, the shape
is (len(distance),...). Otherwise the shape is (...)
- q0: a numpy array of shape (gridn_height,gridn_width,2) containing the
pixel coordinates of each grid cell
- Rt10: the geometric Rt transformation in an array of shape (...,4,3). This is
the relative transformation we ended up using, which is computed using the
logic above (using intrinsics_only and focus_radius). if len(models)>2: this
is an array of shape (len(models)-1,4,3), with slice i representing the
transformation between camera 0 and camera i+1.
- projection_uncertainty(p_cam, model, *, atinfinity=False, what='covariance', observed_pixel_uncertainty=None)
- Compute the projection uncertainty of a camera-referenced point
This is the interface to the uncertainty computations described in
http://mrcal.secretsauce.net/uncertainty.html
SYNOPSIS
model = mrcal.cameramodel("xxx.cameramodel")
q = np.array((123., 443.))
distance = 10.0
pcam = distance * mrcal.unproject(q, *model.intrinsics(), normalize=True)
print(mrcal.projection_uncertainty(pcam,
model = model,
what = 'worstdirection-stdev'))
===> 0.5
# So if we have observed a world point at pixel coordinates q, and we know
# it's 10m out, then we know that the standard deviation of the noise of the
# pixel obsevation is 0.5 pixels, in the worst direction
After a camera model is computed via a calibration process, the model is
ultimately used in projection/unprojection operations to map between world
coordinates and projected pixel coordinates. We never know the parameters of the
model perfectly, and it is VERY useful to know the resulting uncertainty of
projection. This can be used, among other things, to
- propagate the projection noise down to whatever is using the observed pixels
to do stuff
- evaluate the quality of calibrations, to know whether a given calibration
should be accepted, or rejected
- evaluate the stability of a computed model
I quantify uncertainty by propagating expected noise on observed chessboard
corners through the optimization problem we're solving during calibration time
to the solved parameters. And then propagating the noise on the parameters
through projection.
The uncertainties can be visualized with the mrcal-show-projection-uncertainty
tool.
ARGUMENTS
This function accepts an array of camera-referenced points p_cam, a
mrcal.cameramodel object and a few meta-parameters that describe details of the
behavior. This function broadcasts on p_cam only. We accept
- p_cam: a numpy array of shape (..., 3). This is the set of camera-coordinate
points where we're querying uncertainty. if not atinfinity: then the full 3D
coordinates of p_cam are significant, even distance to the camera. if
atinfinity: the distance to the camera is ignored.
- model: a mrcal.cameramodel object that contains optimization_inputs, which are
used to propagate the uncertainty
- atinfinity: optional boolean, defaults to False. If True, we want to know the
projection uncertainty, looking at a point infinitely-far away. We propagate
all the uncertainties, ignoring the translation components of the poses
- what: optional string, defaults to 'covariance'. This chooses what kind of
output we want. Known options are:
- 'covariance': return a full (2,2) covariance matrix Var(q) for
each p_cam
- 'worstdirection-stdev': return the worst-direction standard deviation for
each p_cam
- 'rms-stdev': return the RMS of the worst and best direction
standard deviations
- observed_pixel_uncertainty: optional value, defaulting to None. The
uncertainty of the observed chessboard corners being propagated through the
solve and projection. If omitted or None, this input uncertainty is inferred
from the residuals at the optimum. Most people should omit this
RETURN VALUE
A numpy array of uncertainties. If p_cam has shape (..., 3) then:
if what == 'covariance': we return an array of shape (..., 2,2)
else: we return an array of shape (...)
- qt_from_Rt(Rt, *, out=None)
- Compute a qt transformation from a Rt transformation
SYNOPSIS
Rt = nps.glue(rotation_matrix,translation, axis=-2)
print(Rt.shape)
===>
(4,3)
qt = mrcal.qt_from_Rt(Rt)
print(qt.shape)
===>
(7,)
quat = qt[:4]
translation = qt[4:]
Converts an Rt transformation to a qt transformation. Both specify a rotation
and translation. An Rt transformation is a (4,3) array formed by nps.glue(R,t,
axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector.
A qt transformation is a (7,) array formed by nps.glue(q,t, axis=-1) where q is
a (4,) unit quaternion and t is a (3,) translation vector.
Applied to a point x the transformed result is rotate(x)+t. Given a matrix R,
the rotation is defined by a matrix multiplication. x and t are stored as a row
vector (that's how numpy stores 1-dimensional arrays), but the multiplication
works as if x was a column vector (to match linear algebra conventions). See the
docs for mrcal._transform_point_Rt() for more detail.
This function supports broadcasting fully.
Note: mrcal does not use unit quaternions anywhere to represent rotations. This
function is provided for convenience, but isn't thoroughly tested.
ARGUMENTS
- Rt: array of shape (4,3). This matrix defines the transformation. Rt[:3,:] is
a rotation matrix; Rt[3,:] is a translation. It is assumed that the rotation
matrix is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that
is not checked
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg.
RETURNED VALUE
We return the qt transformation. Each broadcasted slice has shape (7,). qt[:4]
is a rotation defined as a unit quaternion; qt[4:] is a translation.
- quat_from_R(R, *, out=None)
- Convert a rotation defined as a rotation matrix to a unit quaternion
SYNOPSIS
print(R.shape)
===>
(3,3)
quat = mrcal.quat_from_R(R)
print(quat.shape)
===>
(4,)
c = quat[0]
s = nps.mag(quat[1:])
rotation_magnitude = 2. * np.arctan2(s,c)
rotation_axis = quat[1:] / s
This is mostly for compatibility with some old stuff. mrcal doesn't use
quaternions anywhere. Test this thoroughly before using.
This function supports broadcasting fully.
ARGUMENTS
- R: array of shape (3,3,). The rotation matrix that defines the rotation.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If 'out'
is given, we return the 'out' that was passed in. This is the standard
behavior provided by numpysane_pywrap.
RETURNED VALUE
We return an array of unit quaternions. Each broadcasted slice has shape (4,).
The values in the array are (u,i,j,k)
LICENSE AND COPYRIGHT
The implementation comes directly from the scipy project, the from_dcm()
function in
https://github.com/scipy/scipy/blob/master/scipy/spatial/transform/rotation.py
Commit: 1169d27ad47a29abafa8a3d2cb5b67ff0df80a8f
License:
Copyright (c) 2001-2002 Enthought, Inc. 2003-2019, SciPy Developers.
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
1. Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above
copyright notice, this list of conditions and the following
disclaimer in the documentation and/or other materials provided
with the distribution.
3. Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived
from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- r_from_R(R, *, get_gradients=False, out=None)
- Compute a Rodrigues vector from a rotation matrix
SYNOPSIS
r = mrcal.r_from_R(R)
rotation_magnitude = nps.mag(r)
rotation_axis = r / rotation_magnitude
Given a rotation specified as a (3,3) rotation matrix, converts it to a
Rodrigues vector, a unit rotation axis scaled by the rotation magnitude, in
radians.
By default this function returns the Rodrigues vector(s) only. If we also want
gradients, pass get_gradients=True. Logic:
if not get_gradients: return r
else: return (r, dr/dR)
This function supports broadcasting fully.
ARGUMENTS
- R: array of shape (3,3). This matrix defines the rotation. It is assumed that
this is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that
is not checked
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of Rodrigues vectors. Otherwise we return a tuple of arrays of Rodrigues
vectors and their gradients.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return an array of Rodrigues vector(s). Each
broadcasted slice has shape (3,)
If get_gradients: we return a tuple of arrays containing the Rodrigues vector(s)
and the gradients (r, dr/dR)
1. The Rodrigues vector. Each broadcasted slice has shape (3,)
2. The gradient dr/dR. Each broadcasted slice has shape (3,3,3). The first
dimension selects the element of r, and the last two dimensions select the
element of R
- rectification_maps(models, models_rectified)
- Construct image transformation maps to make rectified images
SYNOPSIS
import sys
import mrcal
import cv2
import numpy as np
import numpysane as nps
models = [ mrcal.cameramodel(f) \
for f in ('left.cameramodel',
'right.cameramodel') ]
images = [ mrcal.load_image(f) \
for f in ('left.jpg', 'right.jpg') ]
models_rectified = \
mrcal.rectified_system(models,
az_fov_deg = 120,
el_fov_deg = 100)
rectification_maps = mrcal.rectification_maps(models, models_rectified)
images_rectified = [ mrcal.transform_image(images[i], rectification_maps[i]) \
for i in range(2) ]
# Find stereo correspondences using OpenCV
block_size = 3
max_disp = 160 # in pixels
matcher = \
cv2.StereoSGBM_create(minDisparity = 0,
numDisparities = max_disp,
blockSize = block_size,
P1 = 8 *3*block_size*block_size,
P2 = 32*3*block_size*block_size,
uniquenessRatio = 5,
disp12MaxDiff = 1,
speckleWindowSize = 50,
speckleRange = 1)
disparity16 = matcher.compute(*images_rectified) # in pixels*16
# Point cloud in rectified camera-0 coordinates
# shape (H,W,3)
p_rect0 = mrcal.stereo_unproject( disparity16,
models_rectified,
disparity_scale = 16 )
Rt_cam0_rect0 = mrcal.compose_Rt( models [0].extrinsics_Rt_fromref(),
models_rectified[0].extrinsics_Rt_toref() )
# Point cloud in camera-0 coordinates
# shape (H,W,3)
p_cam0 = mrcal.transform_point_Rt(Rt_cam0_rect0, p_rect0)
After the pair of rectified models has been built by mrcal.rectified_system(),
this function can be called to compute the rectification maps. These can be
passed to mrcal.transform_image() to remap input images into the rectified
space.
The documentation for mrcal.rectified_system() applies here.
ARGUMENTS
- models: an iterable of two mrcal.cameramodel objects representing the cameras
in the stereo pair
- models_rectified: the pair of rectified models, corresponding to the input
images. Usually this is returned by mrcal.rectified_system()
RETURNED VALUES
We return a length-2 tuple of numpy arrays containing transformation maps for
each camera. Each map can be used to mrcal.transform_image() images into
rectified space. Each array contains 32-bit floats (as expected by
mrcal.transform_image() and cv2.remap()). Each array has shape (Nel,Naz,2),
where (Nel,Naz) is the shape of each rectified image. Each shape-(2,) row
contains corresponding pixel coordinates in the input image
- rectified_system(models, *, az_fov_deg, el_fov_deg, az0_deg=None, el0_deg=0, pixels_per_deg_az=-1.0, pixels_per_deg_el=-1.0, rectification_model='LENSMODEL_LATLON', return_metadata=False)
- Build rectified models for stereo rectification
SYNOPSIS
import sys
import mrcal
import cv2
import numpy as np
import numpysane as nps
models = [ mrcal.cameramodel(f) \
for f in ('left.cameramodel',
'right.cameramodel') ]
images = [ mrcal.load_image(f) \
for f in ('left.jpg', 'right.jpg') ]
models_rectified = \
mrcal.rectified_system(models,
az_fov_deg = 120,
el_fov_deg = 100)
rectification_maps = mrcal.rectification_maps(models, models_rectified)
images_rectified = [ mrcal.transform_image(images[i], rectification_maps[i]) \
for i in range(2) ]
# Find stereo correspondences using OpenCV
block_size = 3
max_disp = 160 # in pixels
matcher = \
cv2.StereoSGBM_create(minDisparity = 0,
numDisparities = max_disp,
blockSize = block_size,
P1 = 8 *3*block_size*block_size,
P2 = 32*3*block_size*block_size,
uniquenessRatio = 5,
disp12MaxDiff = 1,
speckleWindowSize = 50,
speckleRange = 1)
disparity16 = matcher.compute(*images_rectified) # in pixels*16
# Point cloud in rectified camera-0 coordinates
# shape (H,W,3)
p_rect0 = mrcal.stereo_unproject( disparity16,
models_rectified,
disparity_scale = 16 )
Rt_cam0_rect0 = mrcal.compose_Rt( models [0].extrinsics_Rt_fromref(),
models_rectified[0].extrinsics_Rt_toref() )
# Point cloud in camera-0 coordinates
# shape (H,W,3)
p_cam0 = mrcal.transform_point_Rt(Rt_cam0_rect0, p_rect0)
This function computes the parameters of a rectified system from two
cameramodels in a stereo pair. The output is a pair of "rectified" models. Each
of these is a normal mrcal.cameramodel object describing a "camera" somewhere in
space, with some particular projection behavior. The pair of models returned
here have the desired property that each row of pixels represents a plane in
space AND each corresponding row in the pair of rectified images represents the
SAME plane: the epipolar lines are aligned. We can use the rectified models
returned by this function to transform the input images into "rectified" images,
and then we can perform stereo matching efficiently, by treating each row
independently.
This function is generic: the two input cameras may use any lens models, any
resolution and any geometry. They don't even have to match. As long as there's
some non-zero baseline and some overlapping views, we can run stereo processing.
The two rectified models describe the poses of the rectified cameras. Each
rectified camera sits at the same position as the input camera, but with a
different orientation. The orientations of the two cameras in the rectified
system are identical. The only difference between the poses of the two rectified
cameras is a translation of the second camera along the x axis. The axes of the
rectified coordinate system:
- x: from the origin of the first camera to the origin of the second camera (the
baseline direction)
- y: completes the system from x,z
- z: the mean "forward" direction of the two input cameras, with the component
parallel to the baseline subtracted off
In a nominal geometry (the two cameras are square with each other, the second
camera strictly to the right of the first camera), the geometry of the rectified
models exactly matches the geometry of the input models. The above formulation
supports any geometry, however, including vertical and/or forward/backward
shifts. Vertical stereo is supported: we still run stereo matching on ROWS of
the rectified images, but the rectification transformation will rotate the
images by 90 degrees.
Several projection functions may be used in the rectified system. These are
selectable using the "rectification_model" keyword argument; they're a string
representing the lensmodel that will be used in the cameramodel objects we
return. Two projections are currently supported:
- "LENSMODEL_LATLON": the default projection that utilizes a transverse
equirectangular map. This projection has even angular spacing between pixels,
so it works well even with wide lenses. The documentation has more information:
http://mrcal.secretsauce.net/lensmodels.html#lensmodel-latlon
- "LENSMODEL_PINHOLE": the traditional projection function that utilizes a
pinhole camera. This works badly with wide lenses, and is recommended if
compatibility with other stereo processes is desired
ARGUMENTS
- models: an iterable of two mrcal.cameramodel objects representing the cameras
in the stereo pair. Any sane combination of lens models and resolutions and
geometries is valid
- az_fov_deg: required value for the azimuth (along-the-baseline) field-of-view
of the desired rectified system, in degrees
- el_fov_deg: required value for the elevation (across-the-baseline)
field-of-view of the desired rectified system, in degrees. Note that this
applies at the center of the rectified system: az = 0. With a skewed stereo
system (if we have a forward/backward shift or if a nonzero az0_deg is given),
this rectification center will not be at the horizontal center of the image,
and may not be in-bounds of the image at all.
- az0_deg: optional value for the azimuth center of the rectified images. This
is especially significant in a camera system with some forward/backward shift.
That causes the baseline to no longer be perpendicular with the view axis of
the cameras, and thus the azimuth=0 vector no longer points "forward". If
omitted, we compute az0_deg to align the center of the rectified system with
the center of the two cameras' views. This computed value can be retrieved in
the metadata dict by passing return_metadata = True
- el0_deg: optional value for the elevation center of the rectified system.
Defaults to 0.
- pixels_per_deg_az: optional value for the azimuth resolution of the rectified
image. If a resultion of >0 is requested, the value is used as is. If a
resolution of <0 is requested, we use this as a scale factor on the resolution
of the first input image. For instance, to downsample by a factor of 2, pass
pixels_per_deg_az = -0.5. By default, we use -1: the resolution of the input
image at the center of the rectified system. The value we end up with can be
retrieved in the metadata dict by passing return_metadata = True
- pixels_per_deg_el: same as pixels_per_deg_az but in the elevation direction
- rectification_model: optional string that selects the projection function to
use in the resulting rectified system. This is a string selecting the mrcal
lens model. Currently supported are "LENSMODEL_LATLON" (the default) and
"LENSMODEL_PINHOLE"
- return_metadata: optional boolean, defaulting to False. If True, we return a
dict of metadata describing the rectified system in addition to the rectified
models. This is useful to retrieve any of the autodetected values. At this
time, the metadata dict contains keys:
- az_fov_deg
- el_fov_deg
- az0_deg
- el0_deg
- pixels_per_deg_az
- pixels_per_deg_el
- baseline
RETURNED VALUES
We compute a tuple of mrcal.cameramodels describing the two rectified cameras.
These two models are identical, except for a baseline translation in the +x
direction in rectified coordinates.
if not return_metadata: we return this tuple of models
else: we return this tuple of models, dict of metadata
- reduce(...)
- reduce(function, iterable[, initial]) -> value
Apply a function of two arguments cumulatively to the items of a sequence
or iterable, from left to right, so as to reduce the iterable to a single
value. For example, reduce(lambda x, y: x+y, [1, 2, 3, 4, 5]) calculates
((((1+2)+3)+4)+5). If initial is present, it is placed before the items
of the iterable in the calculation, and serves as a default when the
iterable is empty.
- ref_calibration_object(W, H, object_spacing, *, calobject_warp=None)
- Return the geometry of the calibration object
SYNOPSIS
import gnuplotlib as gp
import numpysane as nps
obj = mrcal.ref_calibration_object( 10,6, 0.1 )
print(obj.shape)
===> (6, 10, 3)
gp.plot( nps.clump( obj[...,:2], n=2),
tuplesize = -2,
_with = 'points',
_xrange = (-0.1,1.0),
_yrange = (-0.1,0.6),
unset = 'grid',
square = True,
terminal = 'dumb 74,45')
0.6 +---------------------------------------------------------------+
| + + + + + |
| |
0.5 |-+ A A A A A A A A A A +-|
| |
| |
0.4 |-+ A A A A A A A A A A +-|
| |
| |
0.3 |-+ A A A A A A A A A A +-|
| |
| |
0.2 |-+ A A A A A A A A A A +-|
| |
| |
0.1 |-+ A A A A A A A A A A +-|
| |
| |
0 |-+ A A A A A A A A A A +-|
| |
| + + + + + |
-0.1 +---------------------------------------------------------------+
0 0.2 0.4 0.6 0.8 1
Returns the geometry of a calibration object in its own reference coordinate
system in a (H,W,3) array. Only a grid-of-points calibration object is
supported, possibly with some bowing (i.e. what the internal mrcal solver
supports). Each row of the output is an (x,y,z) point. The origin is at the
corner of the grid, so ref_calibration_object(...)[0,0,:] is
np.array((0,0,0)). The grid spans x and y, with z representing the depth: z=0
for a flat calibration object.
A simple parabolic board warping model is supported by passing a (2,) array in
calobject_warp. These 2 values describe additive flex along the x axis and along
the y axis, in that order. In each direction the flex is a parabola, with the
parameter k describing the max deflection at the center. If the edges were at
+-1 we'd have
z = k*(1 - x^2)
The edges we DO have are at (0,N-1), so the equivalent expression is
xr = x / (N-1)
z = k*( 1 - 4*xr^2 + 4*xr - 1 ) =
4*k*(xr - xr^2) =
ARGUMENTS
- W: how many points we have in the horizontal direction
- H: how many points we have in the vertical direction
- object_spacing: the distance between adjacent points in the calibration
object. If a scalar is given, a square object is assumed, and the vertical and
horizontal distances are assumed to be identical. An array of shape (..., 2)
can be given: the last dimension is (spacing_h, spacing_w), and the preceding
dimensions are used for broadcasting
- calobject_warp: optional array of shape (2,) defaults to None. Describes the
warping of the calibration object. If None, the object is flat. If an array is
given, the values describe the maximum additive deflection along the x and y
axes. Extended array can be given for broadcasting
This function supports broadcasting across object_spacing and calobject_warp
RETURNED VALUES
The calibration object geometry in a (..., H,W,3) array, with the leading
dimensions set by the broadcasting rules
- residuals_chessboard(optimization_inputs, *, i_cam=None, residuals=None)
- Compute and return the chessboard residuals
SYNOPSIS
model = mrcal.cameramodel(model_filename)
gp.plot( mrcal.residuals_chessboard(
optimization_inputs = model.optimization_inputs(),
i_cam = i_cam ).ravel(),
histogram = True,
binwidth = 0.02 )
... A plot pops up showing the empirical distribution of chessboard fit
... errors in this solve. For ALL the cameras
Given a calibration solve, returns the residuals of chessboard observations,
throwing out outliers and, optionally, selecting the residuals from a specific
camera.
ARGUMENTS
- optimization_inputs: the optimization inputs dict passed into and returned
from mrcal.optimize(). This describes the solved optimization problem that
we're visualizing
- i_cam: optional integer to select the camera whose residuals we're visualizing
If omitted or None, we report the residuals for ALL the cameras together.
- residuals: optional numpy array of shape (Nmeasurements,) containing the
optimization residuals. If omitted or None, this will be recomputed. To use a
cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or
mrcal.optimizer_callback(**optimization_inputs)[1]
RETURNED VALUES
Numpy array of shape (N,2) of all the residuals. N is the number of pixel
observations remaining after outliers and other cameras are thrown out
- rotate_point_R(R, x, *, get_gradients=False, out=None, inverted=False)
- Rotate point(s) using a rotation matrix
SYNOPSIS
r = rotation_axis * rotation_magnitude
R = mrcal.R_from_r(r)
print(R.shape)
===>
(3,3)
print(x.shape)
===>
(10,3)
print( mrcal.rotate_point_R(R, x).shape )
===>
(10,3)
print( [arr.shape for arr in mrcal.rotate_point_R(R, x,
get_gradients = True)] )
===>
[(10,3), (10,3,3,3), (10,3,3)]
Rotate point(s) by a rotation matrix. This is a matrix multiplication. x is
stored as a row vector (that's how numpy stores 1-dimensional arrays), but the
multiplication works as if x was a column vector (to match linear algebra
conventions):
rotate_point_R(R,x) = transpose( matmult(R, transpose(x))) =
= matmult(x, transpose(R))
By default this function returns the rotated points only. If we also want
gradients, pass get_gradients=True. Logic:
if not get_gradients: return u=R(x)
else: return (u=R(x),du/dR,du/dx)
This function supports broadcasting fully, so we can rotate lots of points at
the same time and/or apply lots of different rotations at the same time
In-place operation is supported; the output array may be the same as the input
arrays to overwrite the input.
ARGUMENTS
- R: array of shape (3,3). This matrix defines the rotation. It is assumed that
this is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that
is not checked
- x: array of shape (3,). The point being rotated
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of rotated points. Otherwise we return a tuple of arrays of rotated
points and their gradients.
- inverted: optional boolean, defaulting to False. If True, the opposite
rotation is computed. The gradient du/dR is returned in respect to the input R
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return an array of rotated point(s). Each broadcasted
slice has shape (3,)
If get_gradients: we return a tuple of arrays containing the rotated points and
the gradients (u=R(x),du/dR,du/dx):
1. The rotated point(s). Each broadcasted slice has shape (3,)
2. The gradient du/dR. Each broadcasted slice has shape (3,3,3). The first
dimension selects the element of u, and the last 2 dimensions select the
element of R
3. The gradient du/dx. Each broadcasted slice has shape (3,3). The first
dimension selects the element of u, and the last dimension selects the
element of x
- rotate_point_r(r, x, *, get_gradients=False, out=None, inverted=False)
- Rotate point(s) using a Rodrigues vector
SYNOPSIS
r = rotation_axis * rotation_magnitude
print(r.shape)
===>
(3,)
print(x.shape)
===>
(10,3)
print(mrcal.rotate_point_r(r, x).shape)
===>
(10,3)
print( [arr.shape for arr in mrcal.rotate_point_r(r, x,
get_gradients = True)] )
===>
[(10,3), (10,3,3), (10,3,3)]
Rotate point(s) by a rotation matrix. The Rodrigues vector is converted to a
rotation matrix internally, and then this function is a matrix multiplication. x
is stored as a row vector (that's how numpy stores 1-dimensional arrays), but
the multiplication works as if x was a column vector (to match linear algebra
conventions):
rotate_point_r(r,x) = transpose( matmult(R(r), transpose(x))) =
= matmult(x, transpose(R(r)))
By default this function returns the rotated points only. If we also want
gradients, pass get_gradients=True. Logic:
if not get_gradients: return u=r(x)
else: return (u=r(x),du/dr,du/dx)
This function supports broadcasting fully, so we can rotate lots of points at
the same time and/or apply lots of different rotations at the same time
In-place operation is supported; the output array may be the same as the input
arrays to overwrite the input.
ARGUMENTS
- r: array of shape (3,). The Rodrigues vector that defines the rotation. This is
a unit rotation axis scaled by the rotation magnitude, in radians
- x: array of shape (3,). The point being rotated
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of rotated points. Otherwise we return a tuple of arrays of rotated
points and their gradients.
- inverted: optional boolean, defaulting to False. If True, the opposite
rotation is computed. The gradient du/dr is returned in respect to the input r
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return an array of rotated point(s). Each broadcasted
slice has shape (3,)
If get_gradients: we return a tuple of arrays containing the rotated points and
the gradients (u=r(x),du/dr,du/dx):
A tuple (u=r(x),du/dr,du/dx):
1. The rotated point(s). Each broadcasted slice has shape (3,)
2. The gradient du/dr. Each broadcasted slice has shape (3,3). The first
dimension selects the element of u, and the last dimension selects the
element of r
3. The gradient du/dx. Each broadcasted slice has shape (3,3). The first
dimension selects the element of u, and the last dimension selects the
element of x
- rt_from_Rt(Rt, *, get_gradients=False, out=None)
- Compute an rt transformation from a Rt transformation
SYNOPSIS
Rt = nps.glue(rotation_matrix,translation, axis=-2)
print(Rt.shape)
===>
(4,3)
rt = mrcal.rt_from_Rt(Rt)
print(rt.shape)
===>
(6,)
translation = rt[3:]
rotation_magnitude = nps.mag(rt[:3])
rotation_axis = rt[:3] / rotation_magnitude
Converts an Rt transformation to an rt transformation. Both specify a rotation
and translation. An Rt transformation is a (4,3) array formed by nps.glue(R,t,
axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector.
An rt transformation is a (6,) array formed by nps.glue(r,t, axis=-1) where r is
a (3,) Rodrigues vector and t is a (3,) translation vector.
Applied to a point x the transformed result is rotate(x)+t. Given a matrix R,
the rotation is defined by a matrix multiplication. x and t are stored as a row
vector (that's how numpy stores 1-dimensional arrays), but the multiplication
works as if x was a column vector (to match linear algebra conventions). See the
docs for mrcal._transform_point_Rt() for more detail.
By default this function returns the rt transformations only. If we also want
gradients, pass get_gradients=True. Logic:
if not get_gradients: return rt
else: return (rt, dr/dR)
Note that the translation gradient isn't returned: it is always the identity
This function supports broadcasting fully.
ARGUMENTS
- Rt: array of shape (4,3). This matrix defines the transformation. Rt[:3,:] is
a rotation matrix; Rt[3,:] is a translation. It is assumed that the rotation
matrix is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that
is not checked
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of rt transformations. Otherwise we return a tuple of arrays of rt
transformations and their gradients.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return the rt transformation. Each broadcasted slice
has shape (6,). rt[:3] is a rotation defined as a Rodrigues vector; rt[3:] is a
translation.
If get_gradients: we return a tuple of arrays containing the rt transformation
and the gradient (rt, dr/dR):
1. The rt transformation. Each broadcasted slice has shape (6,)
2. The gradient dr/dR. Each broadcasted slice has shape (3,3,3). The first
dimension selects the element of r, and the last two dimension select the
element of R
- sample_imager(gridn_width, gridn_height, imager_width, imager_height)
- Returns regularly-sampled, gridded pixels coordinates across the imager
SYNOPSIS
q = sample_imager( 60, 40, *model.imagersize() )
print(q.shape)
===>
(40,60,2)
Note that the arguments are given in width,height order, as is customary when
generally talking about images and indexing. However, the output is in
height,width order, as is customary when talking about matrices and numpy
arrays.
If we ask for gridding dimensions (gridn_width, gridn_height), the output has
shape (gridn_height,gridn_width,2) where each row is an (x,y) pixel coordinate.
The top-left corner is at [0,0,:]:
sample_imager(...)[0,0] = [0,0]
The the bottom-right corner is at [-1,-1,:]:
sample_imager(...)[ -1, -1,:] =
sample_imager(...)[gridn_height-1,gridn_width-1,:] =
(imager_width-1,imager_height-1)
When making plots you probably want to call mrcal.imagergrid_using(). See the
that docstring for details.
ARGUMENTS
- gridn_width: how many points along the horizontal gridding dimension
- gridn_height: how many points along the vertical gridding dimension. If None,
we compute an integer gridn_height to maintain a square-ish grid:
gridn_height/gridn_width ~ imager_height/imager_width
- imager_width,imager_height: the width, height of the imager. With a
mrcal.cameramodel object this is *model.imagersize()
RETURNED VALUES
We return an array of shape (gridn_height,gridn_width,2). Each row is an (x,y)
pixel coordinate.
- sample_imager_unproject(gridn_width, gridn_height, imager_width, imager_height, lensmodel, intrinsics_data, normalize=False)
- Reports 3D observation vectors that regularly sample the imager
SYNOPSIS
import gnuplotlib as gp
import mrcal
...
Nwidth = 60
Nheight = 40
# shape (Nheight,Nwidth,3)
v,q = \
mrcal.sample_imager_unproject(Nw, Nh,
*model.imagersize(),
*model.intrinsics())
# shape (Nheight,Nwidth)
f = interesting_quantity(v)
gp.plot(f,
tuplesize = 3,
ascii = True,
using = mrcal.imagergrid_using(model.imagersize, Nw, Nh),
square = True,
_with = 'image')
This is a utility function used by functions that evalute some interesting
quantity for various locations across the imager. Grid dimensions and lens
parameters are passed in, and the grid points and corresponding unprojected
vectors are returned. The unprojected vectors are unique only up-to-length, and
the returned vectors aren't normalized by default. If we want them to be
normalized, pass normalize=True.
This function has two modes of operation:
- One camera. lensmodel is a string, and intrinsics_data is a 1-dimensions numpy
array. With a mrcal.cameramodel object together these are *model.intrinsics().
We return (v,q) where v is a shape (Nheight,Nwidth,3) array of observation
vectors, and q is a (Nheight,Nwidth,2) array of corresponding pixel
coordinates (the grid returned by sample_imager())
- Multiple cameras. lensmodel is a list or tuple of strings; intrinsics_data is
an iterable of 1-dimensional numpy arrays (a list/tuple or a 2D array). We
return the same q as before (only one camera is gridded), but the unprojected
array v has shape (Ncameras,Nheight,Nwidth,3) where Ncameras is the leading
dimension of lensmodel. The gridded imager appears in camera0: v[0,...] =
unproject(q)
ARGUMENTS
- gridn_width: how many points along the horizontal gridding dimension
- gridn_height: how many points along the vertical gridding dimension. If None,
we compute an integer gridn_height to maintain a square-ish grid:
gridn_height/gridn_width ~ imager_height/imager_width
- imager_width,imager_height: the width, height of the imager. With a
mrcal.cameramodel object this is *model.imagersize()
- lensmodel, intrinsics_data: the lens parameters. With a single camera,
lensmodel is a string, and intrinsics_data is a 1-dimensions numpy array; with
a mrcal.cameramodel object together these are *model.intrinsics(). With
multiple cameras, lensmodel is a list/tuple of strings. And intrinsics_data is
an iterable of 1-dimensional numpy arrays (a list/tuple or a 2D array).
- normalize: optional boolean defaults to False. If True: normalize the output
vectors
RETURNED VALUES
We return a tuple:
- v: the unprojected vectors. If we have a single camera this has shape
(Nheight,Nwidth,3). With multiple cameras this has shape
(Ncameras,Nheight,Nwidth,3). These are NOT normalized by default. To get
normalized vectors, pass normalize=True
- q: the imager-sampling grid. This has shape (Nheight,Nwidth,2) regardless of
how many cameras were given (we always sample just one camera). This is what
sample_imager() returns
- save_image(...)
- Save a numpy array to an image on disk
SYNOPSIS
print(image.shape)
---> (768, 1024, 3)
print(image.dtype)
---> dtype('uint8')
mrcal.save_image("result.png", image)
# wrote BGR color image to disk
This is a completely uninteresting image-saving routine. It's like any other
image-saving routine out there; use any that you like. This exists because cv2
is very slow.
This wraps the mrcal_image_TYPE_save() functions. At this time I support only
these 3 data formats:
- bpp = 8, channels = 1: 8-bit grayscale data
- bpp = 16, channels = 1: 16-bit grayscale data
- bpp = 24, channels = 3: BGR color data
ARGUMENTS
- filename: the image on disk to save to
- array: numpy array containing the input data. Must have shape (height,width)
for grayscale data or (height,width,3) for color data. Each row must be stored
densely, but a non-dense stride is supported when moving from column to
column. The dtype must be either np.uint8 or np.uint16.
RETURNED VALUE
None on success. Exception thrown on error
- scale_focal__best_pinhole_fit(model, fit)
- Compute the optimal focal-length scale for reprojection to a pinhole lens
SYNOPSIS
model = mrcal.cameramodel('from.cameramodel')
lensmodel,intrinsics_data = model.intrinsics()
scale_focal = mrcal.scale_focal__best_pinhole_fit(model,
'centers-horizontal')
intrinsics_data[:2] *= scale_focal
model_pinhole = \
mrcal.cameramodel(intrinsics = ('LENSMODEL_PINHOLE',
intrinsics_data[:4]),
imagersize = model.imagersize(),
extrinsics_rt_fromref = model.extrinsics_rt_fromref() )
Many algorithms work with images assumed to have been captured with a pinhole
camera, even though real-world lenses never fit a pinhole model. mrcal provides
several functions to remap images captured with non-pinhole lenses into images
of the same scene as if they were observed by a pinhole lens. When doing this,
we're free to choose all of the parameters of this pinhole lens model, and this
function allows us to pick the best scaling on the focal-length parameter.
The focal length parameters serve as a "zoom" factor: changing these parameters
can increase the resolution of the center of the image, at the expense of
cutting off the edges. This function computes the best focal-length scaling, for
several possible meanings of "best".
I assume an output pinhole model that has pinhole parameters
(k*fx, k*fy, cx, cy)
where (fx, fy, cx, cy) are the parameters from the input model, and k is the
scaling we compute.
This function looks at some points on the edge of the input image. I choose k so
that all of these points end up inside the pinhole-reprojected image, leaving
the worst one at the edge. The set of points I look at are specified in the
"fit" argument.
ARGUMENTS
- model: a mrcal.cameramodel object for the input lens model
- fit: which pixel coordinates in the input image must project into the output
pinhole-projected image. The 'fit' argument must be one of
- a numpy array of shape (N,2) where each row is a pixel coordinate in the
input image
- "corners": each of the 4 corners of the input image must project into the
output image
- "centers-horizontal": the two points at the left and right edges of the
input image, half-way vertically, must both project into the output image
- "centers-vertical": the two points at the top and bottom edges of the input
image, half-way horizontally, must both project into the output image
RETURNED VALUE
A scalar scale_focal that can be passed to pinhole_model_for_reprojection()
- seed_stereographic(imagersizes, focal_estimate, indices_frame_camera, observations, object_spacing)
- Compute an optimization seed for a camera calibration
SYNOPSIS
print( imagersizes.shape )
===>
(4, 2)
print( indices_frame_camera.shape )
===>
(123, 2)
print( observations.shape )
===>
(123, 3)
intrinsics_data, \
extrinsics_rt_fromref, \
frames_rt_toref = \
mrcal.seed_stereographic(imagersizes = imagersizes,
focal_estimate = 1500,
indices_frame_camera = indices_frame_camera,
observations = observations,
object_spacing = object_spacing)
....
mrcal.optimize(intrinsics_data, extrinsics_rt_fromref, frames_rt_toref,
lensmodel = 'LENSMODEL_STEREOGRAPHIC',
...)
mrcal solves camera calibration problems by iteratively optimizing a nonlinear
least squares problem to bring the pixel observation predictions in line with
actual pixel observations. This requires an initial "seed", an initial estimate
of the solution. This function computes a usable seed, and its results can be
fed to mrcal.optimize(). The output of this function is just an initial estimate
that will be refined, so the results of this function do not need to be exact.
This function assumes we have stereographic lenses, and the returned intrinsics
apply to LENSMODEL_STEREOGRAPHIC. This is usually good-enough to serve as a seed
for both long lenses and wide lenses, every ultra-wide fisheyes. The returned
intrinsics can be expanded to whatever lens model we actually want to use prior
to invoking the optimizer.
By convention, we have a "reference" coordinate system that ties the poses of
all the frames (calibration objects) and the cameras together. And by
convention, this "reference" coordinate system is the coordinate system of
camera 0. Thus the array of camera poses extrinsics_rt_fromref holds Ncameras-1
transformations: the first camera has an identity transformation, by definition.
This function assumes we're observing a moving object from stationary cameras
(i.e. a vanilla camera calibration problem). The mrcal solver is more general,
and supports moving cameras, hence it uses a more general
indices_frame_camintrinsics_camextrinsics array instead of the
indices_frame_camera array used here.
See test/test-basic-calibration.py and mrcal-calibrate-cameras for usage
examples.
ARGUMENTS
- imagersizes: an iterable of (imager_width,imager_height) iterables. Defines
the imager dimensions for each camera we're calibrating. May be an array of
shape (Ncameras,2) or a tuple of tuples or a mix of the two
- focal_estimate: an initial estimate of the focal length of the cameras, in
pixels. For the purposes of the initial estimate we assume the same focal
length value for both the x and y focal length. This argument can be
- a scalar: this is applied to all the cameras
- an iterable of length 1: this value is applied to all the cameras
- an iterable of length Ncameras: each camera uses a different value
- indices_frame_camera: an array of shape (Nobservations,2) and dtype
numpy.int32. Each row (iframe,icam) represents an observation of a
calibration object by camera icam. iframe is not used by this function
- observations: an array of shape
(Nobservations,object_height_n,object_width_n,3). Each observation corresponds
to a row in indices_frame_camera, and contains a row of shape (3,) for each
point in the calibration object. Each row is (x,y,weight) where x,y are the
observed pixel coordinates. Any point where x<0 or y<0 or weight<0 is ignored.
This is the only use of the weight in this function.
- object_spacing: the distance between adjacent points in the calibration
object. A square object is assumed, so the vertical and horizontal distances
are assumed to be identical. Usually we need the object dimensions in the
object_height_n,object_width_n arguments, but here we get those from the shape
of the observations array
RETURNED VALUES
We return a tuple:
- intrinsics_data: an array of shape (Ncameras,4). Each slice contains the
stereographic intrinsics for the given camera. These intrinsics are
(focal_x,focal_y,centerpixel_x,centerpixel_y), and define
LENSMODEL_STEREOGRAPHIC model. mrcal refers to these 4 values as the
"intrinsics core". For models that have such a core (currently, ALL supported
models), the core is the first 4 parameters of the intrinsics vector. So to
calibrate some cameras, call seed_stereographic(), append to intrinsics_data
the proper number of parameters to match whatever lens model we're using, and
then invoke the optimizer.
- extrinsics_rt_fromref: an array of shape (Ncameras-1,6). Each slice is an rt
transformation TO the camera coordinate system FROM the reference coordinate
system. By convention camera 0 defines the reference coordinate system, so
that camera's extrinsics are the identity, by definition, and we don't store
that data in this array
- frames_rt_toref: an array of shape (Nframes,6). Each slice represents the pose
of the calibration object at one instant in time: an rt transformation TO the
reference coordinate system FROM the calibration object coordinate system.
- shellquote = quote(s)
- Return a shell-escaped version of the string *s*.
- show_distortion_off_pinhole(model, *, vectorfield=False, vectorscale=1.0, cbmax=25.0, gridn_width=60, gridn_height=None, extratitle=None, return_plot_args=False, **kwargs)
- Visualize a lens's deviation from a pinhole projection
SYNOPSIS
model = mrcal.cameramodel('xxx.cameramodel')
mrcal.show_distortion_off_pinhole( model )
... A plot pops up displaying how much this model deviates from a pinhole
... model across the imager
This function treats a pinhole projection as a baseline, and visualizes
deviations from this baseline. So wide lenses will have a lot of reported
"distortion".
ARGUMENTS
- model: the mrcal.cameramodel object being evaluated
- vectorfield: optional boolean, defaulting to False. By default we produce a
heat map of the differences. If vectorfield: we produce a vector field
instead
- vectorscale: optional value, defaulting to 1.0. Applicable only if
vectorfield. The magnitude of the errors displayed in the vector field could
be small, and difficult to see. This argument can be used to scale all the
displayed vectors to improve legibility.
- cbmax: optional value, defaulting to 25.0. Sets the maximum range of the color
map and of the contours if plotting a heat map
- gridn_width: how many points along the horizontal gridding dimension
- gridn_height: how many points along the vertical gridding dimension. If None,
we compute an integer gridn_height to maintain a square-ish grid:
gridn_height/gridn_width ~ imager_height/imager_width
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUE
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
if return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_distortion_off_pinhole_radial(model, *, show_fisheye_projections=False, extratitle=None, return_plot_args=False, **kwargs)
- Visualize a lens's deviation from a pinhole projection
SYNOPSIS
model = mrcal.cameramodel('xxx.cameramodel')
mrcal.show_distortion_off_pinhole_radial(model)
... A plot pops up displaying how much this model deviates from a pinhole
... model across the imager in the radial direction
This function treats a pinhole projection as a baseline, and visualizes
deviations from this baseline. So wide lenses will have a lot of reported
"distortion".
This function looks at radial distortion only. Plots a curve showing the
magnitude of the radial distortion as a function of the distance to the center
ARGUMENTS
- model: the mrcal.cameramodel object being evaluated
- show_fisheye_projections: optional boolean defaulting to False. If
show_fisheye_projections: the radial plots include the behavior of common
fisheye projections, in addition to the behavior of THIS lens
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUE
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
if return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_geometry(models_or_extrinsics_rt_fromref, *, cameranames=None, cameras_Rt_plot_ref=None, frames_rt_toref=None, points=None, show_calobjects='all', axis_scale=None, object_width_n=None, object_height_n=None, object_spacing=0, calobject_warp=None, point_labels=None, extratitle=None, return_plot_args=False, **kwargs)
- Visualize the world resulting from a calibration run
SYNOPSIS
# Visualize the geometry from some models on disk
models = [mrcal.cameramodel(m) for m in model_filenames]
plot1 = mrcal.show_geometry(models)
# Solve a calibration problem. Visualize the resulting geometry AND the
# observed calibration objects and points
...
mrcal.optimize(intrinsics,
extrinsics_rt_fromref,
frames_rt_toref,
points,
...)
plot2 = \
mrcal.show_geometry(extrinsics_rt_fromref,
frames_rt_toref = frames_rt_toref,
points = points,
xlabel = 'Northing (m)',
ylabel = 'Easting (m)',
zlabel = 'Down (m)')
This function visualizes the world described by a set of camera models. It shows
- The geometry of the cameras themselves. Each one is represented by the axes of
its coordinate system
- The geometry of the calibration objects used to compute these models. These
are shown only if available and requested
- Available: The data comes either from the frames_rt_toref argument or from
the first model.optimization_inputs() that is given. If we have both, we use
the frames_rt_toref
- Requested: if we're using frames_rt_toref then we show the calibration
objects if show_calobjects. I.e. show_calobjects is treated as a boolean.
If we're using a model.optimization_inputs() then we can have finer-grained
control. if show_calobjects == 'all': we show ALL the calibration objects,
observed by ANY camera. elif show_calobjects == 'thiscamera': we only show
the calibration objects that were observed by the given camera at
calibration time. As before, if we have multiple camera models with multiple
optimization_inputs, we use the first one
This function can also be used to visualize the output (or input) of
mrcal.optimize(); the relevant parameters are all identical to those
mrcal.optimize() takes.
This function is the core of the mrcal-show-geometry tool.
All arguments except models_or_extrinsics_rt_fromref are optional.
Extra **kwargs are passed directly to gnuplotlib to control the plot.
ARGUMENTS
- models_or_extrinsics_rt_fromref: an iterable of mrcal.cameramodel objects or
(6,) rt arrays. A array of shape (N,6) works to represent N cameras. If
mrcal.cameramodel objects are given here and frames_rt_toref is omitted, we
get the frames_rt_toref from the first model that provides
optimization_inputs().
- cameranames: optional array of strings of labels for the cameras. If omitted,
we use generic labels. If given, the array must have the same length as
models_or_extrinsics_rt_fromref
- cameras_Rt_plot_ref: optional transformation(s). If omitted, we plot
everything in the camera reference coordinate system. If given, we use a
"plot" coordinate system with the transformation TO plot coordinates FROM the
reference coordinates given in this argument. This argument can be given as an
iterable of Rt transformations to use a different one for each camera (None
means "identity"). Or a single Rt transformation can be given to use that one
for ALL the cameras
- frames_rt_toref: optional array of shape (N,6). If given, each row of shape
(6,) is an rt transformation representing the transformation TO the reference
coordinate system FROM the calibration object coordinate system. The
calibration object then MUST be defined by passing in valid object_width_n,
object_height_n, object_spacing parameters. If frames_rt_toref is omitted or
None, we look for this data in the given camera models. I look at the given
models in order, and grab the frames from the first model that has them. If
none of the models have this data and frames_rt_toref is omitted or NULL, then
I don't plot any frames at all
- object_width_n: the number of horizontal points in the calibration object
grid. Required only if frames_rt_toref is not None
- object_height_n: the number of vertical points in the calibration object grid.
Required only if frames_rt_toref is not None
- object_spacing: the distance between adjacent points in the calibration
object. A square object is assumed, so the vertical and horizontal distances
are assumed to be identical. Required only if frames_rt_toref is not None
- calobject_warp: optional (2,) array describing the calibration board warping.
None means "no warping": the object is flat. Used only if frames_rt_toref is
not None. See the docs for mrcal.ref_calibration_object() for a description.
- points: optional array of shape (N,3). If omitted, we don't plot the observed
points. If given, each row of shape (3,) is a point in the reference
coordinate system.
- point_labels: optional dict from a point index to a string describing it.
Points in this dict are plotted with this legend; all other points are plotted
under a generic "points" legend. As many or as few of the points may be
labelled in this way. If omitted, none of the points will be labelled
specially. This is used only if points is not None
- show_calobjects: optional string defaults to 'all'. if show_calobjects: we
render the observed calibration objects (if they are available in
frames_rt_toref or model.optimization_inputs()['frames_rt_toref']; we look at
the FIRST model that provides this data). If we have optimization_inputs and
show_calobjects == 'all': we display the objects observed by ANY camera. elif
show_calobjects == 'thiscamera': we only show those observed by THIS camera.
- axis_scale: optional scale factor for the size of the axes used to represent
the cameras. Can be omitted to use some reasonable default size, but tweaking
it might be necessary to make the plot look right. If less than 1 camera is
given, this defaults to 1.0. If at least 2 cameras are given, we default to
1/4 the distance between the FIRST pair of cameras
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, set the plot title, etc.
RETURNED VALUES
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
if return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_projection_diff(models, *, implied_Rt10=None, gridn_width=60, gridn_height=None, observations=False, valid_intrinsics_region=False, intrinsics_only=False, distance=None, use_uncertainties=True, focus_center=None, focus_radius=-1.0, vectorfield=False, vectorscale=1.0, directions=False, cbmax=4, extratitle=None, return_plot_args=False, **kwargs)
- Visualize the difference in projection between N models
SYNOPSIS
models = ( mrcal.cameramodel('cam0-dance0.cameramodel'),
mrcal.cameramodel('cam0-dance1.cameramodel') )
mrcal.show_projection_diff(models)
# A plot pops up displaying the projection difference between the two models
The operation of this tool is documented at
http://mrcal.secretsauce.net/differencing.html
This function visualizes the results of mrcal.projection_diff()
It is often useful to compare the projection behavior of two camera models. For
instance, one may want to validate a calibration by comparing the results of two
different chessboard dances. Or one may want to evaluate the stability of the
intrinsics in response to mechanical or thermal stresses.
In the most common case we're given exactly 2 models to compare. We then display
the projection difference as either a vector field or a heat map. If we're given
more than 2 models, then a vector field isn't possible and we instead display as
a heatmap the standard deviation of the differences between models 1..N and
model0.
The top-level operation of this function:
- Grid the imager
- Unproject each point in the grid using one camera model
- Apply a transformation to map this point from one camera's coord system to the
other. How we obtain this transformation is described below
- Project the transformed points to the other camera
- Look at the resulting pixel difference in the reprojection
If implied_Rt10 is given, we simply use that as the transformation (this is
currently supported ONLY for diffing exactly 2 cameras). If implied_Rt10 is not
given, we estimate it. Several variables control this. Top-level logic:
if intrinsics_only:
Rt10 = identity_Rt()
else:
if focus_radius == 0:
Rt10 = relative_extrinsics(models)
else:
Rt10 = implied_Rt10__from_unprojections()
The details of how the comparison is computed, and the meaning of the arguments
controlling this, are in the docstring of mrcal.projection_diff().
ARGUMENTS
- models: iterable of mrcal.cameramodel objects we're comparing. Usually there
will be 2 of these, but more than 2 is possible. The intrinsics are used; the
extrinsics are NOT.
- implied_Rt10: optional transformation to use to line up the camera coordinate
systems. Most of the time we want to estimate this transformation, so this
should be omitted or None. Currently this is supported only if exactly two
models are being compared.
- gridn_width: optional value, defaulting to 60. How many points along the
horizontal gridding dimension
- gridn_height: how many points along the vertical gridding dimension. If None,
we compute an integer gridn_height to maintain a square-ish grid:
gridn_height/gridn_width ~ imager_height/imager_width
- observations: optional value, defaulting to False. If observations: we overlay
calibration-time observations on top of the difference plot. We should then
see that more data produces more consistent results. If a special value of
'dots' is passed, the observations are plotted as dots instead of points
- valid_intrinsics_region: optional boolean, defaulting to False. If True, we
overlay the valid-intrinsics regions onto the plot. If the valid-intrinsics
regions aren't available, we will silently omit them
- intrinsics_only: optional boolean, defaulting to False. If True: we evaluate
the intrinsics of each lens in isolation by assuming that the coordinate
systems of each camera line up exactly
- distance: optional value, defaulting to None. Has an effect only if not
intrinsics_only. The projection difference varies depending on the range to
the observed world points, with the queried range set in this 'distance'
argument. If None (the default) we look out to infinity. We can compute the
implied-by-the-intrinsics transformation off multiple distances if they're
given here as an iterable. This is especially useful if we have uncertainties,
since then we'll emphasize the best-fitting distances. If multiple distances
are given, the generated plot displays the difference using the FIRST distance
in the list
- use_uncertainties: optional boolean, defaulting to True. Used only if not
intrinsics_only and focus_radius!=0. If True we use the whole imager to fit
the implied-by-the-intrinsics transformation, using the uncertainties to
emphasize the confident regions. If False, it is important to select the
confident region using the focus_center and focus_radius arguments. If
use_uncertainties is True, but that data isn't available, we report a warning,
and try to proceed without.
- focus_center: optional array of shape (2,); the imager center by default. Used
only if not intrinsics_only and focus_radius!=0. Used to indicate that the
implied-by-the-intrinsics transformation should use only those pixels a
distance focus_radius from focus_center. This is intended to be used if no
uncertainties are available, and we need to manually select the focus region.
- focus_radius: optional value. If use_uncertainties then the default is LARGE,
to use the whole imager. Else the default is min(width,height)/6. Used to
indicate that the implied-by-the-intrinsics transformation should use only
those pixels a distance focus_radius from focus_center. This is intended to be
used if no uncertainties are available, and we need to manually select the
focus region. To avoid computing the transformation, either pass
focus_radius=0 (to use the extrinsics in the given models) or pass
intrinsics_only=True (to use the identity transform).
- vectorfield: optional boolean, defaulting to False. By default we produce a
heat map of the projection differences. If vectorfield: we produce a vector
field instead. This is more busy, and is often less clear at first glance, but
unlike a heat map, this shows the directions of the differences in addition to
the magnitude. This is only valid if we're given exactly two models to compare
- vectorscale: optional value, defaulting to 1.0. Applicable only if
vectorfield. The magnitude of the errors displayed in the vector field is
often very small, and impossible to make out when looking at the whole imager.
This argument can be used to scale all the displayed vectors to improve
legibility.
- directions: optional boolean, defaulting to False. By default the plot is
color-coded by the magnitude of the difference vectors. If directions: we
color-code by the direction instead. This is especially useful if we're
plotting a vector field. This is only valid if we're given exactly two models
to compare
- cbmax: optional value, defaulting to 4.0. Sets the maximum range of the color
map
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUE
A tuple:
- if not return_plot_args (the usual path): the gnuplotlib plot object. The plot
disappears when this object is destroyed (by the garbage collection, for
instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
if return_plot_args: a (data_tuples, plot_options) tuple. The plot can then be
made with gp.plot(*data_tuples, **plot_options). Useful if we want to include
this as a part of a more complex plot
- Rt10: the geometric Rt transformation in an array of shape (...,4,3). This is
the relative transformation we ended up using, which is computed using the
logic above (using intrinsics_only and focus_radius). if len(models)>2: this
is an array of shape (len(models)-1,4,3), with slice i representing the
transformation between camera 0 and camera i+1.
- show_projection_uncertainty(model, *, gridn_width=60, gridn_height=None, observed_pixel_uncertainty=None, observations=False, valid_intrinsics_region=False, distance=None, isotropic=False, cbmax=3, contour_increment=None, contour_labels_styles='boxed', contour_labels_font=None, extratitle=None, return_plot_args=False, **kwargs)
- Visualize the uncertainty in camera projection
SYNOPSIS
model = mrcal.cameramodel('xxx.cameramodel')
mrcal.show_projection_uncertainty(model)
... A plot pops up displaying the expected projection uncertainty across the
... imager
This function uses the expected noise of the calibration-time observations to
estimate the uncertainty of projection of the final model. At calibration time we estimate
- The intrinsics (lens paramaters) of a number of cameras
- The extrinsics (geometry) of a number of cameras in respect to some reference
coordinate system
- The poses of observed chessboards, also in respect to some reference
coordinate system
All the coordinate systems move around, and all 3 of these sets of data have
some uncertainty. This tool takes into account all the uncertainties to report
an estimated uncertainty metric. See
http://mrcal.secretsauce.net/uncertainty.html for a detailed description of
the computation.
This function grids the imager, and reports an uncertainty for each point on the
grid. The resulting plot contains a heatmap of the uncertainties for each cell
in the grid, and corresponding contours.
Since the projection uncertainty is based on calibration-time observation
uncertainty, it is sometimes useful to see where the calibration-time
observations were. Pass observations=True to do that.
Since the projection uncertainty is based partly on the uncertainty of the
camera pose, points at different distance from the camera will have different
reported uncertainties EVEN IF THEY PROJECT TO THE SAME PIXEL. The queried
distance is passed in the distance argument. If distance is None (the default)
then we look out to infinity.
For each cell we compute the covariance matrix of the projected (x,y) coords,
and by default we report the worst-direction standard deviation. If isotropic:
we report the RMS standard deviation instead.
ARGUMENTS
- model: the mrcal.cameramodel object being evaluated
- gridn_width: optional value, defaulting to 60. How many points along the
horizontal gridding dimension
- gridn_height: how many points along the vertical gridding dimension. If None,
we compute an integer gridn_height to maintain a square-ish grid:
gridn_height/gridn_width ~ imager_height/imager_width
- observed_pixel_uncertainty: optional value, defaulting to None. The
uncertainty of the observed chessboard corners being propagated through the
solve and projection. If omitted or None, this input uncertainty is inferred
from the residuals at the optimum. Most people should omit this
- observations: optional value, defaulting to False. If observatoins:, we
overlay calibration-time observations on top of the uncertainty plot. We
should then see that more data produces more confident results. If a special
value of 'dots' is passed, the observations are plotted as dots instead of
points
- valid_intrinsics_region: optional boolean, defaulting to False. If True, we
overlay the valid-intrinsics region onto the plot. If the valid-intrinsics
region isn't available, we will silently omit it
- distance: optional value, defaulting to None. The projection uncertainty
varies depending on the range to the observed point, with the queried range
set in this 'distance' argument. If None (the default) we look out to
infinity.
- isotropic: optional boolean, defaulting to False. We compute the full 2x2
covariance matrix of the projection. The 1-sigma contour implied by this
matrix is an ellipse, and we use the worst-case direction by default. If we
want the RMS size of the ellipse instead of the worst-direction size, pass
isotropic=True.
- cbmax: optional value, defaulting to 3.0. Sets the maximum range of the color
map
- contour_increment: optional value, defaulting to None. If given, this will be
used as the distance between adjacent contours. If omitted of None, a
reasonable value will be estimated
- contour_labels_styles: optional string, defaulting to 'boxed'. The style of
the contour labels. This will be passed to gnuplot as f"with labels
{contour_labels_styles} nosurface". Can be used to box/unbox the label, set
the color, etc. To change the font use contour_labels_font.
- contour_labels_font: optional string, defaulting to None, If given, this is
the font string for the contour labels. Will be passed to gnuplot as f'set
cntrlabel font "{contour_labels_font}"'
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUE
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
if return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_projection_uncertainty_vs_distance(model, *, where='centroid', isotropic=False, extratitle=None, return_plot_args=False, **kwargs)
- Visualize the uncertainty in camera projection along one observation ray
SYNOPSIS
model = mrcal.cameramodel('xxx.cameramodel')
mrcal.show_projection_uncertainty_vs_distance(model)
... A plot pops up displaying the expected projection uncertainty along an
... observation ray at different distances from the camera
This function is similar to show_projection_uncertainty(). That function
displays the uncertainty at different locations along the imager, for one
observation distance. Conversely, THIS function displays it in one location on
the imager, but at different distances.
This function uses the expected noise of the calibration-time observations to
estimate the uncertainty of projection of the final model. At calibration time
we estimate
- The intrinsics (lens paramaters) of a number of cameras
- The extrinsics (geometry) of a number of cameras in respect to some reference
coordinate system
- The poses of observed chessboards, also in respect to some reference
coordinate system
All the coordinate systems move around, and all 3 of these sets of data have
some uncertainty. This tool takes into account all the uncertainties to report
an estimated uncertainty metric. See
http://mrcal.secretsauce.net/uncertainty.html for a detailed description of
the computation.
The curve produced by this function has a characteristic shape:
- At low ranges, the camera translation dominates, and the uncertainty increases
to infinity, as the distance to the camera goes to 0
- As we move away from the camera, the uncertainty drops to a minimum, at around
the distance where the chessboards were observed
- Past the minimum, the uncertainty climbs to asymptotically approach the
uncertainty at infinity
ARGUMENTS
- model: the mrcal.cameramodel object being evaluated
- where: optional value, defaulting to "centroid". Indicates the point on the
imager we're examining. May be one of
- "center": the center of the imager
- "centroid": the midpoint of all the chessboard corners observed at
calibration time
- A numpy array (x,y) indicating the pixel
- isotropic: optional boolean, defaulting to False. We compute the full 2x2
covariance matrix of the projection. The 1-sigma contour implied by this
matrix is an ellipse, and we use the worst-case direction by default. If we
want the RMS size of the ellipse instead of the worst-direction size, pass
isotropic=True.
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUE
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
if return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_residuals_board_observation(optimization_inputs, i_observation, *, from_worst=False, i_observations_sorted_from_worst=None, residuals=None, paths=None, image_path_prefix=None, image_directory=None, circlescale=1.0, vectorscale=1.0, showimage=True, extratitle=None, return_plot_args=False, **kwargs)
- Visualize calibration residuals for a single observation
SYNOPSIS
model = mrcal.cameramodel(model_filename)
mrcal.show_residuals_board_observation( model.optimization_inputs(),
0,
from_worst = True )
... A plot pops up showing the worst-fitting chessboard observation from
... the calibration run that produced the model in model_filename
Given a calibration solve, visualizes the fit for a single observation. Plots
the chessboard image overlaid with its residuals. Each residual is plotted as a
circle and a vector. The circles are color-coded by the residual error. The size
of the circle indicates the weight. Bigger means higher weight. The vector shows
the weighted residual from the observation to the prediction.
ARGUMENTS
- optimization_inputs: the optimization inputs dict passed into and returned
from mrcal.optimize(). This describes the solved optimization problem that
we're visualizing
- i_observation: integer that selects the chessboard observation. If not
from_worst (the default), this indexes sequential observations, in the order
in which they appear in the optimization problem. If from_worst: the
observations are indexed in order from the worst-fitting to the best-fitting:
i_observation=0 refers to the worst-fitting observation. This is very useful
to investigate issues in the calibration
- from_worst: optional boolean, defaulting to False. If not from_worst (the
default), i_observation indexes sequential observations, in the order in which
they appear in the optimization problem. If from_worst: the observations are
indexed in order from the worst-fitting to the best-fitting: i_observation=0
refers to the worst-fitting observation. This is very useful to investigate
issues in the calibration
- i_observations_sorted_from_worst: optional iterable of integers used to
convert sorted-from-worst observation indices to as-specified observation
indices. If omitted or None, this will be recomputed. To use a cached value,
pass in a precomputed value. See the sources for an example of how to compute
it
- residuals: optional numpy array of shape (Nmeasurements,) containing the
optimization residuals. If omitted or None, this will be recomputed. To use a
cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or
mrcal.optimizer_callback(**optimization_inputs)[1]
- paths: optional iterable of strings, containing image filenames corresponding
to each observation. If omitted or None or if the image couldn't be found, the
residuals will be plotted without the source image. The path we search is
controlled by the image_path_prefix and image_directory options
- image_path_prefix: optional argument, defaulting to None, exclusive with
"image_directory". If given, the image paths in the "paths" argument are
prefixed with the given string.
- image_directory: optional argument, defaulting to None, exclusive with
"image_path_prefix". If given, we extract the filename from the image path in
the "paths" argument, and look for the images in the directory given here
instead
- circlescale: optional scale factor to adjust the size of the plotted circles.
If omitted, a unit scale (1.0) is used. This exists to improve the legibility
of the generated plot
- vectorscale: optional scale factor to adjust the length of the plotted
vectors. If omitted, a unit scale (1.0) is used: this results in the vectors
representing pixel errors directly. This exists to improve the legibility of
the generated plot
- showimage: optional boolean, defaulting to True. If False, we do NOT plot the
image beneath the residuals.
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUES
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
If return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_residuals_directions(model, residuals=None, *, valid_intrinsics_region=True, extratitle=None, return_plot_args=False, **kwargs)
- Visualize the optimized residual directions as color-coded points
SYNOPSIS
model = mrcal.cameramodel(model_filename)
mrcal.show_residuals_directions( model )
... A plot pops up showing each observation from this camera used to
... compute this calibration. Each displayed point represents an
... observation and the direction of its fit error coded as a color
Given a calibration solve, visualizes the errors at the optimal solution. Each
point sits at the observed chessboard corner, with its color representing the
direction of the fit error. Magnitudes are ignored: large errors and small
errors are displayed identically as long as they're off in the same direction.
This is very useful to detect systematic errors in a solve due to an
insufficiently-flexible camera model.
ARGUMENTS
- model: the mrcal.cameramodel object representing the camera model we're
investigating. This cameramodel MUST contain the optimization_inputs data
- residuals: optional numpy array of shape (Nmeasurements,) containing the
optimization residuals. If omitted or None, this will be recomputed. To use a
cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or
mrcal.optimizer_callback(**optimization_inputs)[1]
- valid_intrinsics_region: optional boolean, defaulting to True. If
valid_intrinsics_region: the valid-intrinsics region present in the model is
shown in the plot. This is usually interesting to compare to the set of
observations plotted by the rest of this function
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUES
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
If return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_residuals_histogram(optimization_inputs, i_cam=None, residuals=None, *, binwidth=0.02, extratitle=None, return_plot_args=False, **kwargs)
- Visualize the distribution of the optimized residuals
SYNOPSIS
model = mrcal.cameramodel(model_filename)
mrcal.show_residuals_histogram( model.optimization_inputs() )
... A plot pops up showing the empirical distribution of fit errors
... in this solve. For ALL the cameras
Given a calibration solve, visualizes the distribution of errors at the optimal
solution. We display a histogram of residuals and overlay it with an idealized
gaussian distribution.
ARGUMENTS
- optimization_inputs: the optimization inputs dict passed into and returned
from mrcal.optimize(). This describes the solved optimization problem that
we're visualizing
- i_cam: optional integer to select the camera whose residuals we're visualizing
If omitted or None, we display the residuals for ALL the cameras together.
- residuals: optional numpy array of shape (Nmeasurements,) containing the
optimization residuals. If omitted or None, this will be recomputed. To use a
cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or
mrcal.optimizer_callback(**optimization_inputs)[1]
- binwidth: optional floating-point value selecting the width of each bin in the
computed histogram. A default of 0.02 pixels is used if this value is omitted.
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUES
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
If return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_residuals_magnitudes(model, residuals=None, *, valid_intrinsics_region=True, extratitle=None, return_plot_args=False, **kwargs)
- Visualize the optimized residual magnitudes as color-coded points
SYNOPSIS
model = mrcal.cameramodel(model_filename)
mrcal.show_residuals_magnitudes( model )
... A plot pops up showing each observation from this camera used to
... compute this calibration. Each displayed point represents an
... observation and its fit error coded as a color
Given a calibration solve, visualizes the errors at the optimal solution. Each
point sits at the observed chessboard corner, with its color representing how
well the solved model fits the observation
ARGUMENTS
- model: the mrcal.cameramodel object representing the camera model we're
investigating. This cameramodel MUST contain the optimization_inputs data
- residuals: optional numpy array of shape (Nmeasurements,) containing the
optimization residuals. If omitted or None, this will be recomputed. To use a
cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or
mrcal.optimizer_callback(**optimization_inputs)[1]
- valid_intrinsics_region: optional boolean, defaulting to True. If
valid_intrinsics_region: the valid-intrinsics region present in the model is
shown in the plot. This is usually interesting to compare to the set of
observations plotted by the rest of this function
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUES
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
If return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_residuals_regional(model, residuals=None, *, gridn_width=20, gridn_height=None, valid_intrinsics_region=True, extratitle=None, return_plot_args=False, **kwargs)
- Visualize the optimized residuals, broken up by region
SYNOPSIS
model = mrcal.cameramodel(model_filename)
mrcal.show_residuals_regional( model )
... Three plots pop up, showing the mean, standard deviation and the count
... of residuals in each region in the imager
This serves as a simple method of estimating calibration reliability, without
computing the projection uncertainty.
The imager of a camera is subdivided into bins (controlled by the gridn_width,
gridn_height arguments). The residual statistics are then computed for each bin
separately. We can then clearly see areas of insufficient data (observation
counts will be low). And we can clearly see lens-model-induced biases (non-zero
mean) and we can see heteroscedasticity (uneven standard deviation). The
mrcal-calibrate-cameras tool uses these metrics to construct a valid-intrinsics
region for the models it computes. This serves as a quick/dirty method of
modeling projection reliability, which can be used even if projection
uncertainty cannot be computed.
ARGUMENTS
- model: the mrcal.cameramodel object representing the camera model we're
investigating. This cameramodel MUST contain the optimization_inputs data
- gridn_width: optional value, defaulting to 20. How many bins along the
horizontal gridding dimension
- gridn_height: how many bins along the vertical gridding dimension. If None, we
compute an integer gridn_height to maintain a square-ish grid:
gridn_height/gridn_width ~ imager_height/imager_width
- residuals: optional numpy array of shape (Nmeasurements,) containing the
optimization residuals. If omitted or None, this will be recomputed. To use a
cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or
mrcal.optimizer_callback(**optimization_inputs)[1]
- valid_intrinsics_region: optional boolean, defaulting to True. If
valid_intrinsics_region: the valid-intrinsics region present in the model is
shown in the plot. This is usually interesting to compare to the set of
observations plotted by the rest of this function
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc. A "hardcopy" here is a base name:
kwargs['hardcopy']="/a/b/c/d.pdf" will produce plots in "/a/b/c/d.XXX.pdf"
where XXX is the type of plot being made
RETURNED VALUES
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
If return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_residuals_vectorfield(model, residuals=None, *, vectorscale=1.0, valid_intrinsics_region=True, extratitle=None, return_plot_args=False, **kwargs)
- Visualize the optimized residuals as a vector field
SYNOPSIS
model = mrcal.cameramodel(model_filename)
mrcal.show_residuals_vectorfield( model )
... A plot pops up showing each observation from this camera used to
... compute this calibration as a vector field. Each vector shows the
... observed and predicted location of each chessboard corner
Given a calibration solve, visualizes the errors at the optimal solution as a
vector field. Each vector runs from the observed chessboard corner to its
prediction at the optimal solution.
ARGUMENTS
- model: the mrcal.cameramodel object representing the camera model we're
investigating. This cameramodel MUST contain the optimization_inputs data
- residuals: optional numpy array of shape (Nmeasurements,) containing the
optimization residuals. If omitted or None, this will be recomputed. To use a
cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or
mrcal.optimizer_callback(**optimization_inputs)[1]
- vectorscale: optional scale factor to adjust the length of the plotted
vectors. If omitted, a unit scale (1.0) is used. Any other scale factor makes
the tip of each vector run past (or short) of the predicted corner position.
This exists to improve the legibility of the generated plot
- valid_intrinsics_region: optional boolean, defaulting to True. If
valid_intrinsics_region: the valid-intrinsics region present in the model is
shown in the plot. This is usually interesting to compare to the set of
observations plotted by the rest of this function
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUES
if not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
If return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_splined_model_correction(model, *, vectorfield=False, xy=None, imager_domain=False, vectorscale=1.0, valid_intrinsics_region=True, observations=False, gridn_width=60, gridn_height=None, extratitle=None, return_plot_args=False, **kwargs)
- Visualize the projection corrections defined by a splined model
SYNOPSIS
model = mrcal.cameramodel(model_filename)
mrcal.show_splined_model_correction(model)
# A plot pops up displaying the spline knots, the magnitude of the
# corrections defined by the spline surfaces, the spline-in-bounds
# regions and the valid-intrinsics region
Splined models are parametrized by flexible surfaces that define the projection
corrections (off some baseline model), and visualizing these corrections is
useful for understanding the projection behavior. Details of these models are
described in the documentation:
http://mrcal.secretsauce.net/lensmodels.html#splined-stereographic-lens-model
At this time LENSMODEL_SPLINED_STEREOGRAPHIC is the only splined model mrcal
has, so the baseline model is always LENSMODEL_STEREOGRAPHIC. In spots, the
below documentation assumes a stereographic baseline model.
This function can produce a plot in the domain either of the input or the output
of the spline functions.
if not imager_domain:
The default. The plot is presented based on the spline index. With
LENSMODEL_SPLINED_STEREOGRAPHIC, this is the stereographic projection u.
This is the "forward" direction, what the projection operation actually
computes. In this view the knots form a regular grid, and the edge of the
imager forms a (possibly very irregular) curve
if imager_domain:
The plot is presented based on the pixels in the imager. This is the
backward direction: the domain is the OUTPUT of the splined functions. In
this view the knot layout is (possibly highly) irregular. The edge of the
imager is a perfect rectangle.
Separate from the domain, the data can be presented in 3 different ways:
- Magnitude heatmap. This is the default. Selected by "not vectorfield and xy is
None". We plot mag(deltauxy). This displays the deviation from the baseline
model as a heat map.
- Individual heatmap. Selected by "not vectorfield and xy is not None". We plot
deltaux or deltauy, depending on the value of xy. This displays the value of
one of the two splined surfaces individually, as a heat map.
- Vector field. Selected by "bool(vectorfield) is True". Displays the correction
(deltaux, deltauy) as a vector field.
The splined surfaces are defined by control points we call "knots". These knots
are arranged in a fixed grid (defined by the model configuration) with the value
at each knot set in the intrinsics vector.
The configuration selects the control point density and the expected field of
view of the lens. If the fov_x_deg configuration value is too big, many of the
knots will lie well outside the visible area, and will not be used. This is
wasteful. If fov_x_deg is too small, then some parts of the imager will lie
outside of the spline-in-bounds region, resulting in less-flexible projection
behavior at the edges of the imager. So the field of view should roughly match
the actual lens+camera we're using, and we can evaluate that with this function.
This function displays the spline-in-bounds region together with the usable
projection region (either the valid-intrinsics region or the imager bounds).
Ideally, the spline-in-bounds region is slightly bigger than the usable
projection region.
The usable projection region visualized by this function is controlled by the
valid_intrinsics_region argument. If True (the default), we display the
valid-intrinsics region. This is recommended, but keep in mind that this region
is smaller than the full imager, so a fov_x_deg that aligns well for one
calibration may be too small in a subsequent calibration of the same lens. If
the subsequent calibration has better coverage, and thus a bigger
valid-intrinsics region. If not valid_intrinsics_region: we use the imager
bounds instead. The issue here is that the projection near the edges of the
imager is usually poorly-defined because usually there isn't a lot of
calibration data there. This makes the projection behavior at the imager edges
unknowable. Consequently, plotting the projection at the imager edges is usually
too alarming or not alarming enough. Passing valid_intrinsics_region=False is
thus recommended only if we have very good calibration coverage at the edge of
the imager.
ARGUMENTS
- model: the mrcal.cameramodel object being evaluated
- vectorfield: optional boolean defaults to False. if vectorfield: we plot the
stereographic correction deltau as vectors. if not vectorfield (the default):
we plot either deltaux or deltauy or mag(deltauxy) as a heat map. if
vectorfield: xy must be None
- xy: optional string. Must be either 'x' or 'y' or None. Selects the surface
we're looking at. We have a separate surface for the x and y coordinates, with
the two sharing the knot positions. We can display one of the surfaces
individually, or if xy is None: we display the magnitude of the (deltaux,
deltauy) vector. if xy is not None: vectorfield MUST be false
- imager_domain: optional boolean defaults to False. If False: we plot
everything against normalized stereographic coordinates; in this
representation the knots form a regular grid, and the surface domain is a
rectangle, but the imager boundary is curved. If True: we plot everything
against the rendered pixel coordinates; the imager boundary is a rectangle,
while the knots and domain become curved
- vectorscale: optional value defaulting to 1.0. if vectorfield: this is a scale
factor on the length of the vectors. If we have small deltau, longer vectors
increase legibility of the plot.
- valid_intrinsics_region: optional boolean defaults to True. If True: we
communicate the usable projection region to the user by displaying the
valid-intrinsics region. This isn't available in all models. To fall back on
the boundary of the full imager, pass False here. In the usual case of
incomplete calibration-time coverage at the edges, this results in a very
unrealistic representation of reality. Passing True here is strongly
recommended
- observations: optional value, defaulting to False. If observations: we plot
the calibration-time point observations on top of the surface and the knots.
These make it more clear if the unprojectable regions in the model really are
a problem. If a special value of 'dots' is passed, the observations are
plotted as dots instead of points
- gridn_width: optional value, defaulting to 60. How many points along the
horizontal gridding dimension
- gridn_height: how many points along the vertical gridding dimension. If None,
we compute an integer gridn_height to maintain a square-ish grid:
gridn_height/gridn_width ~ imager_height/imager_width
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUES
If not return_plot_args (the usual path): we return the gnuplotlib plot object.
The plot disappears when this object is destroyed (by the garbage collection,
for instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
if return_plot_args: we return a (data_tuples, plot_options) tuple instead of
making the plot. The plot can then be made with gp.plot(*data_tuples,
**plot_options). Useful if we want to include this as a part of a more complex
plot
- show_valid_intrinsics_region(models, *, cameranames=None, image=None, points=None, extratitle=None, return_plot_args=False, **kwargs)
- Visualize a model's valid-intrinsics region
SYNOPSIS
filenames = ('cam0-dance0.cameramodel',
'cam0-dance1.cameramodel')
models = [ mrcal.cameramodel(f) for f in filenames ]
mrcal.show_valid_intrinsics_region( models,
cameranames = filenames,
image = 'image.jpg' )
This function displays the valid-intrinsics region in the given camera models.
Multiple models can be passed-in to see their valid-intrinsics regions together.
This is useful to evaluate different calibrations of the same lens. A captured
image can be passed-in to see the regions overlaid on an actual image produced
by the camera.
All given models MUST have a valid-intrinsics region defined. A model may have
an empty region. This cannot be plotted (there's no contour to plot), but the
plot legend will still contain an entry for this model, with a note indicating
its emptiness
This tool produces a gnuplotlib plot. To annotate an image array, call
annotate_image__valid_intrinsics_region() instead
ARGUMENTS
- models: an iterable of mrcal.cameramodel objects we're visualizing. If we're
looking at just a single model, it can be passed directly in this argument,
instead of wrapping it into a list.
- cameranames: optional an iterable of labels, one for each model. These will
appear as the legend in the plot. If omitted, we will simply enumerate the
models.
- image: optional image to annotate. May be given as an image filename or an
array of image data. If omitted, we plot the valid-intrinsics region only.
- points: optional array of shape (N,2) of pixel coordinates to plot. If given,
we show these arbitrary points in our plot. Useful to visualize the feature
points used in a vision algorithm to see how reliable they are expected to be
- extratitle: optional string to include in the title of the resulting plot.
Used to extend the default title string. If kwargs['title'] is given, it is
used directly, and the extratitle is ignored
- return_plot_args: boolean defaulting to False. if return_plot_args: we return
a (data_tuples, plot_options) tuple instead of making the plot. The plot can
then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to
include this as a part of a more complex plot
- **kwargs: optional arguments passed verbatim as plot options to gnuplotlib.
Useful to make hardcopies, etc
RETURNED VALUE
A tuple:
- if not return_plot_args (the usual path): the gnuplotlib plot object. The plot
disappears when this object is destroyed (by the garbage collection, for
instance), so save this returned plot object into a variable, even if you're
not going to be doing anything with this object.
if return_plot_args: a (data_tuples, plot_options) tuple. The plot can then be
made with gp.plot(*data_tuples, **plot_options). Useful if we want to include
this as a part of a more complex plot
- skew_symmetric(...)
- Return the skew-symmetric matrix used in a cross product
SYNOPSIS
a = np.array(( 1., 5., 7.))
b = np.array(( 3., -.1, -10.))
A = mrcal.skew_symmetric(a)
print( nps.inner(A,b) )
===>
[-49.3 31. -15.1]
print( np.cross(a,b) )
===>
[-49.3 31. -15.1]
A vector cross-product a x b can be represented as a matrix multiplication A*b
where A is a skew-symmetric matrix based on the vector a. This function computes
this matrix A from the vector a.
This function supports broadcasting fully.
ARGUMENTS
- a: array of shape (3,)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If 'out'
is given, we return the 'out' that was passed in. This is the standard
behavior provided by numpysane_pywrap.
RETURNED VALUE
We return the matrix A in a (3,3) numpy array
- state_index_calobject_warp(...)
- Return the index in the optimization vector of the calibration object warp
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b = mrcal.optimizer_callback(**optimization_inputs)[0]
mrcal.unpack_state(b, **optimization_inputs)
i_state = mrcal.state_index_calobject_warp(**optimization_inputs)
calobject_warp = b[i_state:i_state+2]
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.state_index_...() functions report where particular items end up in the
state vector.
THIS function reports the beginning of the calibration-object warping parameters
in the state vector. This is stored contiguously as a 2-element vector. These
warping parameters describe how the observed calibration object differs from the
expected calibration object. There will always be some difference due to
manufacturing tolerances and temperature and humidity effects.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the location in the state vector where the contiguous
block of variables for the calibration object warping begins. If we're not
optimizing the calibration object shape, returns None
- state_index_extrinsics(...)
- Return the index in the optimization vector of the extrinsics of camera i
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b = mrcal.optimizer_callback(**optimization_inputs)[0]
mrcal.unpack_state(b, **optimization_inputs)
icam_extrinsics = 1
i_state = mrcal.state_index_extrinsics(icam_extrinsics,
**optimization_inputs)
extrinsics_rt_fromref = b[i_state:i_state+6]
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.state_index_...() functions report where particular items end up in the
state vector.
THIS function reports the beginning of the i-th camera extrinsics in the state
vector. The extrinsics are stored contiguously as an "rt transformation": a
3-element rotation represented as a Rodrigues vector followed by a 3-element
translation. These transform points represented in the reference coordinate
system to the coordinate system of the specific camera. Note that mrcal allows
the reference coordinate system to be tied to a particular camera. In this case
the extrinsics of that camera do not appear in the state vector at all, and
icam_extrinsics == -1 in the indices_frame_camintrinsics_camextrinsics
array.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- icam_extrinsics: an integer indicating which camera we're asking about
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the location in the state vector where the contiguous
block of extrinsics for camera icam_extrinsics begins. If we're not optimizing
the extrinsics, or we're asking for an out-of-bounds camera, returns None
- state_index_frames(...)
- Return the index in the optimization vector of the pose of frame i
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b = mrcal.optimizer_callback(**optimization_inputs)[0]
mrcal.unpack_state(b, **optimization_inputs)
iframe = 1
i_state = mrcal.state_index_frames(iframe,
**optimization_inputs)
frames_rt_toref = b[i_state:i_state+6]
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.state_index_...() functions report where particular items end up in the
state vector.
THIS function reports the beginning of the i-th frame pose in the state vector.
Here a "frame" is a pose of the observed calibration object at some instant in
time. The frames are stored contiguously as an "rt transformation": a 3-element
rotation represented as a Rodrigues vector followed by a 3-element translation.
These transform points represented in the internal calibration object coordinate
system to the reference coordinate system.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- iframe: an integer indicating which frame we're asking about
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the location in the state vector where the contiguous
block of variables for frame iframe begins. If we're not optimizing the frames,
or we're asking for an out-of-bounds frame, returns None
- state_index_intrinsics(...)
- Return the index in the optimization vector of the intrinsics of camera i
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b = mrcal.optimizer_callback(**optimization_inputs)[0]
mrcal.unpack_state(b, **optimization_inputs)
icam_intrinsics = 1
i_state = mrcal.state_index_intrinsics(icam_intrinsics,
**optimization_inputs)
Nintrinsics = mrcal.lensmodel_num_params(optimization_inputs['lensmodel'])
intrinsics_data = b[i_state:i_state+Nintrinsics]
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.state_index_...() functions report where particular items end up in the
state vector.
THIS function reports the beginning of the i-th camera intrinsics in the state
vector. The intrinsics are stored contiguously. They consist of a 4-element
"intrinsics core" (focallength-x, focallength-y, centerpixel-x, centerpixel-y)
followed by a lensmodel-specific vector of "distortions". The number of
intrinsics elements (including the core) for a particular lens model can be
queried with mrcal.lensmodel_num_params(lensmodel). Note that
do_optimize_intrinsics_core and do_optimize_intrinsics_distortions can be used
to lock down one or both of those quantities, which would omit them from the
optimization vector.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- icam_intrinsics: an integer indicating which camera we're asking about
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the location in the state vector where the contiguous
block of intrinsics for camera icam_intrinsics begins. If we're not optimizing
the intrinsics, or we're asking for an out-of-bounds camera, returns None
- state_index_points(...)
- Return the index in the optimization vector of the position of point i
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b = mrcal.optimizer_callback(**optimization_inputs)[0]
mrcal.unpack_state(b, **optimization_inputs)
i_point = 1
i_state = mrcal.state_index_points(i_point,
**optimization_inputs)
point = b[i_state:i_state+3]
The optimization algorithm sees its world described in one, big vector of state.
The optimizer doesn't know or care about the meaning of each element of this
vector, but for later analysis, it is useful to know what's what. The
mrcal.state_index_...() functions report where particular items end up in the
state vector.
THIS function reports the beginning of the i-th point in the state vector. The
points are stored contiguously as a 3-element coordinates in the reference
frame.
In order to determine the variable mapping, we need quite a bit of context. If
we have the full set of inputs to the optimization function, we can pass in
those (as shown in the example above). Or we can pass the individual arguments
that are needed (see ARGUMENTS section for the full list). If the optimization
inputs and explicitly-given arguments conflict about the size of some array, the
explicit arguments take precedence. If any array size is not specified, it is
assumed to be 0. Thus most arguments are optional.
ARGUMENTS
- i_point: an integer indicating which point we're asking about
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
Nobservations_board
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
The integer reporting the location in the state vector where the contiguous
block of variables for point i_point begins If we're not optimizing the points,
or we're asking for an out-of-bounds point, returns None
- stereo_range(disparity, models_rectified, *, disparity_scale=1, qrect0=None)
- Compute ranges from observed disparities
SYNOPSIS
import sys
import mrcal
import cv2
import numpy as np
import numpysane as nps
models = [ mrcal.cameramodel(f) \
for f in ('left.cameramodel',
'right.cameramodel') ]
images = [ mrcal.load_image(f) \
for f in ('left.jpg', 'right.jpg') ]
models_rectified = \
mrcal.rectified_system(models,
az_fov_deg = 120,
el_fov_deg = 100)
rectification_maps = mrcal.rectification_maps(models, models_rectified)
images_rectified = [ mrcal.transform_image(images[i], rectification_maps[i]) \
for i in range(2) ]
# Find stereo correspondences using OpenCV
block_size = 3
max_disp = 160 # in pixels
matcher = \
cv2.StereoSGBM_create(minDisparity = 0,
numDisparities = max_disp,
blockSize = block_size,
P1 = 8 *3*block_size*block_size,
P2 = 32*3*block_size*block_size,
uniquenessRatio = 5,
disp12MaxDiff = 1,
speckleWindowSize = 50,
speckleRange = 1)
disparity16 = matcher.compute(*images_rectified) # in pixels*16
# Convert the disparities to range-to-camera0
ranges = mrcal.stereo_range( disparity16,
models_rectified,
disparity_scale = 16 )
H,W = disparity16.shape
# shape (H,W,2)
q = np.ascontiguousarray( \
nps.mv( nps.cat( *np.meshgrid(np.arange(W,dtype=float),
np.arange(H,dtype=float))),
0, -1))
# Point cloud in rectified camera-0 coordinates
# shape (H,W,3)
p_rect0 = \
mrcal.unproject_latlon(q, models_rectified[0].intrinsics()[1]) * \
nps.dummy(ranges, axis=-1)
Rt_cam0_rect0 = mrcal.compose_Rt( models [0].extrinsics_Rt_fromref(),
models_rectified[0].extrinsics_Rt_toref() )
# Point cloud in camera-0 coordinates
# shape (H,W,3)
p_cam0 = mrcal.transform_point_Rt(Rt_cam0_rect0, p_rect0)
As shown in the example above, we can perform stereo processing by building
rectified models and transformation maps, rectifying our images, and then doing
stereo matching to get pixel disparities. The disparities can be converted to
usable geometry by calling one of two functions:
- stereo_range() to convert pixel disparities to ranges
- stereo_unproject() to convert pixel disparities to a point cloud. This is a
superset of stereo_range()
In the most common usage of stereo_range() we take a full disparity IMAGE, and
then convert it to a range IMAGE. In this common case we call
range_image = mrcal.stereo_range(disparity_image, models_rectified)
If we aren't processing the full disparity image, we can pass in an array of
rectified pixel coordinates (in the first rectified camera) in the "qrect0"
argument. These must be broadcastable with the disparity argument. So we
can pass in a scalar for disparity and a single (2,) array for qrect0. Or
we can pass in full arrays for both. Or we can pass in a shape (H,W) image for
disparity, but only a shape (W,2) array for qrect0: this would use the
same qrect0 value for a whole column of disparity, as dictated by the
broadcasting rules. Such identical-az-in-a-column behavior is valid for
LENSMODEL_LATLON stereo, but not for LENSMODEL_PINHOLE stereo. It's the user's
responsibility to know when to omit data like this. When in doubt, pass a
separate qrect0 for each disparity value.
Each epipolar plane looks like this:
camera0
+ . . . .
\ az0
|----------------
| \--------------------
| range \-----------------------
| \-------- p
| a -----/
| -----/
| -----/
|baseline -----/
| -----/
| -----/
| -----/
| -----/
| -----/
| -----/
| -----/
---/ az1
+. . . . .
camera1
The cameras are at the top-left and bottom-left of the figure, looking out to
the right at a point p in space. The observation ray from camera0 makes an angle
az0 with the "forward" direction (here az0 > 0), while the observation ray from
camera1 makes an angle az1 (here az1 < 0). A LENSMODEL_LATLON disparity is a
difference of azimuth angles: disparity ~ az0-az1. A LENSMODEL_PINHOLE disparity
is a scaled difference of tangents: disparity ~ tan(az0)-tan(az1)
The law of sines tells us that
baseline / sin(a) = range / sin(90 + az1)
Thus
range = baseline cos(az1) / sin(a) =
= baseline cos(az1) / sin( 180 - (90-az0 + 90+az1) ) =
= baseline cos(az1) / sin(az0-az1) =
= baseline cos(az0 - az0-az1) / sin(az0-az1)
az0-az1 is the angular disparity. If using LENSMODEL_LATLON, this is what we
have, and this is a usable expression. Otherwise we keep going:
range = baseline cos(az0 - az0-az1) / sin(az0-az1)
= baseline (cos(az0)cos(az0-az1) + sin(az0)sin(az0-az1)) / sin(az0-az1)
= baseline cos(az0)/tan(az0-az1) + sin(az0)
= baseline cos(az0)* (1 + tan(az0)tan(az1))/(tan(az0) - tan(az1)) + sin(az0)
= baseline cos(az0)*((1 + tan(az0)tan(az1))/(tan(az0) - tan(az1)) + tan(az0))
A scaled tan(az0)-tan(az1) is the disparity when using LENSMODEL_PINHOLE, so
this is the final expression we use.
When using LENSMODEL_LATLON, the azimuth values in the projection ARE the
azimuth values inside each epipolar plane, so there's nothing extra to do. When
using LENSMODEL_PINHOLE however, there's an extra step. We need to convert pixel
disparity values to az0 and az1.
Let's say we're looking two rectified pinhole points on the same epipolar plane,
a "forward" point and a "query" point:
q0 = [0, qy] and q1 = [qx1, qy]
We convert these to normalized coords: tanxy = (q-cxy)/fxy
t0 = [0, ty] and t1 = [tx1, ty]
These unproject to
v0 = [0, ty, 1] and v1 = [tx1, ty, 1]
These lie on an epipolar plane with normal [0, -1, ty]. I define a coordinate
system basis using the normal as one axis. The other two axes are
b0 = [1, 0, 0 ]
b1 = [0, ty/L, 1/L]
where L = sqrt(ty^2 + 1)
Projecting my two vectors to (b0,b1) I get
[0, ty^2/L + 1/L]
[tx1, ty^2/L + 1/L]
Thus the the angle this query point makes with the "forward" vector is
tan(az_in_epipolar_plane) = tx1 / ( (ty^2 + 1)/L ) = tx1 / sqrt(ty^2 + 1)
Thus to get tan(az) expressions we use to compute ranges, we need to scale our
(qx1-cx)/fx values by 1./sqrt(ty^2 + 1). This is one reason to use
LENSMODEL_LATLON for stereo processing instead of LENSMODEL_PINHOLE: the az
angular scale stays constant across different el, which produces better stereo
matches.
ARGUMENTS
- disparity: a numpy array of disparities being processed. If disparity_scale is
omitted, this array contains floating-point disparity values in PIXELS. Many
stereo-matching algorithms produce integer disparities, in units of some
constant number of pixels (the OpenCV StereoSGBM and StereoBM routines use
16). In this common case, you can pass the integer scaled disparities here,
with the scale factor in disparity_scale. Any array shape is supported. In the
common case of a disparity IMAGE, this is an array of shape (Nel, Naz)
- models_rectified: the pair of rectified models, corresponding to the input
images. Usually this is returned by mrcal.rectified_system()
- disparity_scale: optional scale factor for the "disparity" array. If omitted,
the "disparity" array is assumed to contain the disparities, in pixels.
Otherwise it contains data in the units of 1/disparity_scale pixels.
- qrect0: optional array of rectified camera0 pixel coordinates corresponding to
the given disparities. By default, a full disparity image is assumed.
Otherwise we use the given rectified coordinates. The shape of this array must
be broadcasting-compatible with the disparity array. See the
description above.
RETURNED VALUES
- An array of ranges of the same dimensionality as the input disparity
array. Contains floating-point data. Invalid or missing ranges are represented
as 0.
- stereo_unproject(disparity, models_rectified, *, ranges=None, disparity_scale=1, qrect0=None)
- Compute a point cloud from observed disparities
SYNOPSIS
import sys
import mrcal
import cv2
import numpy as np
import numpysane as nps
models = [ mrcal.cameramodel(f) \
for f in ('left.cameramodel',
'right.cameramodel') ]
images = [ mrcal.load_image(f) \
for f in ('left.jpg', 'right.jpg') ]
models_rectified = \
mrcal.rectified_system(models,
az_fov_deg = 120,
el_fov_deg = 100)
rectification_maps = mrcal.rectification_maps(models, models_rectified)
images_rectified = [ mrcal.transform_image(images[i], rectification_maps[i]) \
for i in range(2) ]
# Find stereo correspondences using OpenCV
block_size = 3
max_disp = 160 # in pixels
matcher = \
cv2.StereoSGBM_create(minDisparity = 0,
numDisparities = max_disp,
blockSize = block_size,
P1 = 8 *3*block_size*block_size,
P2 = 32*3*block_size*block_size,
uniquenessRatio = 5,
disp12MaxDiff = 1,
speckleWindowSize = 50,
speckleRange = 1)
disparity16 = matcher.compute(*images_rectified) # in pixels*16
# Point cloud in rectified camera-0 coordinates
# shape (H,W,3)
p_rect0 = mrcal.stereo_unproject( disparity16,
models_rectified,
disparity_scale = 16 )
Rt_cam0_rect0 = mrcal.compose_Rt( models [0].extrinsics_Rt_fromref(),
models_rectified[0].extrinsics_Rt_toref() )
# Point cloud in camera-0 coordinates
# shape (H,W,3)
p_cam0 = mrcal.transform_point_Rt(Rt_cam0_rect0, p_rect0)
As shown in the example above, we can perform stereo processing by building
rectified models and transformation maps, rectifying our images, and then doing
stereo matching to get pixel disparities. The disparities can be converted to
usable geometry by calling one of two functions:
- stereo_range() to convert pixel disparities to ranges
- stereo_unproject() to convert pixel disparities to a point cloud, each point in
the rectified-camera-0 coordinates. This is a superset of stereo_range()
In the most common usage of stereo_unproject() we take a full disparity IMAGE,
and then convert it to a dense point cloud: one point per pixel. In this common
case we call
p_rect0 = mrcal.stereo_unproject(disparity_image, models_rectified)
If we aren't processing the full disparity image, we can pass in an array of
rectified pixel coordinates (in the first rectified camera) in the "qrect0"
argument. These must be broadcastable with the disparity argument.
The arguments are identical to those accepted by stereo_range(), except an
optional "ranges" argument is accepted. This can be given in lieu of the
"disparity" argument, if we already have ranges returned by stereo_range().
Exactly one of (disparity,ranges) must be given as non-None. "ranges" is a
keyword-only argument, while "disparity" is positional. So if passing ranges,
the disparity must be explicitly given as None:
p_rect0 = mrcal.stereo_unproject( disparity = None,
models_rectified = models_rectified,
ranges = ranges )
ARGUMENTS
- disparity: a numpy array of disparities being processed. If disparity_scale is
omitted, this array contains floating-point disparity values in PIXELS. Many
stereo-matching algorithms produce integer disparities, in units of some
constant number of pixels (the OpenCV StereoSGBM and StereoBM routines use
16). In this common case, you can pass the integer scaled disparities here,
with the scale factor in disparity_scale. Any array shape is supported. In the
common case of a disparity IMAGE, this is an array of shape (Nel, Naz)
- models_rectified: the pair of rectified models, corresponding to the input
images. Usually this is returned by mrcal.rectified_system()
- ranges: optional numpy array with the ranges returned by stereo_range().
Exactly one of (disparity,ranges) should be given as non-None.
- disparity_scale: optional scale factor for the "disparity" array. If omitted,
the "disparity" array is assumed to contain the disparities, in pixels.
Otherwise it contains data in the units of 1/disparity_scale pixels.
- qrect0: optional array of rectified camera0 pixel coordinates corresponding to
the given disparities. By default, a full disparity image is assumed.
Otherwise we use the given rectified coordinates. The shape of this array must
be broadcasting-compatible with the disparity array. See the
description above.
RETURNED VALUES
- An array of points of the same dimensionality as the input disparity (or
ranges) array. Contains floating-point data. Invalid or missing points are
represented as (0,0,0).
- supported_lensmodels(...)
- Returns a tuple of strings for the various lens models we support
SYNOPSIS
print(mrcal.supported_lensmodels())
('LENSMODEL_PINHOLE',
'LENSMODEL_STEREOGRAPHIC',
'LENSMODEL_SPLINED_STEREOGRAPHIC_...',
'LENSMODEL_OPENCV4',
'LENSMODEL_OPENCV5',
'LENSMODEL_OPENCV8',
'LENSMODEL_OPENCV12',
'LENSMODEL_CAHVOR',
'LENSMODEL_CAHVORE_linearity=...')
mrcal knows about some set of lens models, which can be queried here. The above
list is correct as of this writing, but more models could be added with time.
The returned lens models are all supported, with possible gaps in capabilities.
The capabilities of each model are returned by lensmodel_metadata_and_config().
At this time, the only missing functionality that CAHVORE is gradients aren't
implemented, so we can't compute an optimal CAHVORE model.
Models ending in '...' have configuration parameters given in the model string,
replacing the '...'.
RETURNED VALUE
A tuple of strings listing out all the currently-supported lens models
- synthesize_board_observations(models, *, object_width_n, object_height_n, object_spacing, calobject_warp, rt_ref_boardcenter, rt_ref_boardcenter__noiseradius, Nframes, which='all-cameras-must-see-full-board')
- Produce synthetic chessboard observations
SYNOPSIS
models = [mrcal.cameramodel("0.cameramodel"),
mrcal.cameramodel("1.cameramodel"),]
# shapes (Nframes, Ncameras, object_height_n, object_width_n, 2) and
# (Nframes, 4, 3)
q,Rt_ref_boardref = \
mrcal.synthesize_board_observations( \
models,
# board geometry
object_width_n = 10,
object_height_n = 12,
object_spacing = 0.1,
calobject_warp = None,
# mean board pose and the radius of the added uniform noise
rt_ref_boardcenter = rt_ref_boardcenter
rt_ref_boardcenter__noiseradius = rt_ref_boardcenter__noiseradius,
# How many frames we want
Nframes = 100
which = 'some-cameras-must-see-half-board')
# q now contains the synthetic pixel observations, but some of them will be
# out of view. I construct an (x,y,weight) observations array, as expected
# by the optimizer, and I set the weight for the out-of-view points to -1 to
# tell the optimizer to ignore those points
# Set the weights to 1 initially
# shape (Nframes, Ncameras, object_height_n, object_width_n, 3)
observations = nps.glue(q,
np.ones( q.shape[:-1] + (1,) ),
axis = -1)
# shape (Ncameras, 1, 1, 2)
imagersizes = nps.mv( nps.cat(*[ m.imagersize() for m in models ]),
-2, -4 )
observations[ np.any( q < 0, axis=-1 ), 2 ] = -1.
observations[ np.any( q-imagersizes >= 0, axis=-1 ), 2 ] = -1.
Given a description of a calibration object and of the cameras observing it,
produces perfect pixel observations of the objects by those cameras. We return a
dense observation array: every corner observation from every chessboard pose
will be reported for every camera. Some of these observations MAY be
out-of-view, depending on the value of the 'which' argument; see description
below. The example above demonstrates how to mark such out-of-bounds
observations as outliers to tell the optimization to ignore these.
The "models" provides the intrinsics and extrinsics.
The calibration objects are nominally have pose rt_ref_boardcenter in the
reference coordinate system, with each pose perturbed uniformly with radius
rt_ref_boardcenter__noiseradius. This is nonstandard since here I'm placing the
board origin at its center instead of the corner (as
mrcal.ref_calibration_object() does). But this is more appropriate to the usage
of this function. The returned Rt_ref_boardref transformation DOES use the
normal corner-referenced board geometry
Returns the point observations and the chessboard poses that produced these
observations.
ARGUMENTS
- models: an array of mrcal.cameramodel objects, one for each camera we're
simulating. This is the intrinsics and the extrinsics. Ncameras = len(models)
- object_width_n: the number of horizontal points in the calibration object grid
- object_height_n: the number of vertical points in the calibration object grid
- object_spacing: the distance between adjacent points in the calibration
object. A square object is assumed, so the vertical and horizontal distances
are assumed to be identical.
- calobject_warp: a description of the calibration board warping. None means "no
warping": the object is flat. Otherwise this is an array of shape (2,). See
the docs for ref_calibration_object() for the meaning of the values in this
array.
- rt_ref_boardcenter: the nominal pose of the calibration object, in the
reference coordinate system. This is an rt transformation from a
center-referenced calibration object to the reference coordinate system
- rt_ref_boardcenter__noiseradius: the deviation-from-nominal for the chessboard
pose for each frame. I add uniform noise to rt_ref_boardcenter, with each
element sampled independently, with the radius given here.
- Nframes: how many frames of observations to return
- which: a string, defaulting to 'all-cameras-must-see-full-board'. Controls the
requirements on the visibility of the returned points. Valid values:
- 'all-cameras-must-see-full-board': We return only those chessboard poses
that produce observations that are FULLY visible by ALL the cameras.
- 'some-cameras-must-see-full-board': We return only those chessboard poses
that produce observations that are FULLY visible by AT LEAST ONE camera.
- 'all-cameras-must-see-half-board': We return only those chessboard poses
that produce observations that are AT LEAST HALF visible by ALL the cameras.
- 'some-cameras-must-see-half-board': We return only those chessboard poses
that produce observations that are AT LEAST HALF visible by AT LEAST ONE
camera.
RETURNED VALUES
We return a tuple:
- q: an array of shape (Nframes, Ncameras, object_height, object_width, 2)
containing the pixel coordinates of the generated observations
- Rt_ref_boardref: an array of shape (Nframes, 4,3) containing the poses of the
chessboards. This transforms the object returned by ref_calibration_object()
to the pose that was projected, in the ref coord system
- transform_image(image, mapxy, *, out=None, borderMode=None, borderValue=0, interpolation=None)
- Transforms a given image using a given map
SYNOPSIS
model_orig = mrcal.cameramodel("xxx.cameramodel")
image_orig = mrcal.load_image("image.jpg")
model_pinhole = mrcal.pinhole_model_for_reprojection(model_orig,
fit = "corners")
mapxy = mrcal.image_transformation_map(model_orig, model_pinhole,
intrinsics_only = True)
image_undistorted = mrcal.transform_image(image_orig, mapxy)
# image_undistorted is now a pinhole-reprojected version of image_orig
Given an array of pixel mappings this function can be used to transform one
image to another. If we want to convert a scene image observed by one camera
model to the image of the same scene using a different model, we can produce a
suitable transformation map with mrcal.image_transformation_map(). An example of
this common usage appears above in the synopsis.
At this time this function is a thin wrapper around cv2.remap()
ARGUMENTS
- image: a numpy array containing an image we're transforming. May be grayscale:
shape (Nheight_input, Nwidth_input) or RGB: shape (Nheight_input,
Nwidth_input, 3)
- mapxy: a numpy array of shape (Nheight,Nwidth,2) where Nheight and Nwidth
represent the dimensions of the target image. This array is expected to have
dtype=np.float32, since the internals of this function are provided by
cv2.remap()
- out: optional numpy array of shape (Nheight,Nwidth) or (Nheight,Nwidth,3) to
receive the result. If omitted, a new array is allocated and returned.
- borderMode: optional constant defining out-of-bounds behavior. Defaults to
cv2.BORDER_TRANSPARENT, and is passed directly to cv2.remap(). Please see the
docs for that function for details. This option may disappear if mrcal stops
relying on opencv
- interpolation: optional constant defining pixel interpolation behavior.
Defaults to cv2.INTER_LINEAR, and is passed directly to cv2.remap(). Please
see the docs for that function for details. This option may disappear if mrcal
stops relying on opencv
RETURNED VALUE
A numpy array of shape (Nheight, Nwidth) if grayscale or (Nheight, Nwidth, 3) if
RGB. Contains the transformed image.
- transform_point_Rt(Rt, x, *, get_gradients=False, out=None, inverted=False)
- Transform point(s) using an Rt transformation
SYNOPSIS
Rt = nps.glue(rotation_matrix,translation, axis=-2)
print(Rt.shape)
===>
(4,3)
print(x.shape)
===>
(10,3)
print( mrcal.transform_point_Rt(Rt, x).shape )
===>
(10,3)
print( [arr.shape
for arr in mrcal.transform_point_Rt(Rt, x,
get_gradients = True)] )
===>
[(10,3), (10,3,4,3), (10,3,3)]
Transform point(s) by an Rt transformation: a (4,3) array formed by
nps.glue(R,t, axis=-2) where R is a (3,3) rotation matrix and t is a (3,)
translation vector. This transformation is defined by a matrix multiplication
and an addition. x and t are stored as a row vector (that's how numpy stores
1-dimensional arrays), but the multiplication works as if x was a column vector
(to match linear algebra conventions):
transform_point_Rt(Rt, x) = transpose( matmult(Rt[:3,:], transpose(x)) +
transpose(Rt[3,:]) ) =
= matmult(x, transpose(Rt[:3,:])) +
Rt[3,:]
By default this function returns the transformed points only. If we also want
gradients, pass get_gradients=True. Logic:
if not get_gradients: return u=Rt(x)
else: return (u=Rt(x),du/dRt,du/dx)
This function supports broadcasting fully, so we can transform lots of points at
the same time and/or apply lots of different transformations at the same time
In-place operation is supported; the output array may be the same as the input
arrays to overwrite the input.
ARGUMENTS
- Rt: array of shape (4,3). This matrix defines the transformation. Rt[:3,:] is
a rotation matrix; Rt[3,:] is a translation. It is assumed that the rotation
matrix is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that
is not checked
- x: array of shape (3,). The point being transformed
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of transformed points. Otherwise we return a tuple of arrays of
transformed points and their gradients.
- inverted: optional boolean, defaulting to False. If True, the opposite
transformation is computed. The gradient du/dRt is returned in respect to the
input Rt
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return an array of transformed point(s). Each
broadcasted slice has shape (3,)
If get_gradients: we return a tuple of arrays of transformed points and the
gradients (u=Rt(x),du/dRt,du/dx):
1. The transformed point(s). Each broadcasted slice has shape (3,)
2. The gradient du/dRt. Each broadcasted slice has shape (3,4,3). The first
dimension selects the element of u, and the last 2 dimensions select the
element of Rt
3. The gradient du/dx. Each broadcasted slice has shape (3,3). The first
dimension selects the element of u, and the last dimension selects the
element of x
- transform_point_rt(rt, x, *, get_gradients=False, out=None, inverted=False)
- Transform point(s) using an rt transformation
SYNOPSIS
r = rotation_axis * rotation_magnitude
rt = nps.glue(r,t, axis=-1)
print(rt.shape)
===>
(6,)
print(x.shape)
===>
(10,3)
print( mrcal.transform_point_rt(rt, x).shape )
===>
(10,3)
print( [arr.shape
for arr in mrcal.transform_point_rt(rt, x,
get_gradients = True)] )
===>
[(10,3), (10,3,6), (10,3,3)]
Transform point(s) by an rt transformation: a (6,) array formed by
nps.glue(r,t, axis=-1) where r is a (3,) Rodrigues vector and t is a (3,)
translation vector. This transformation is defined by a matrix multiplication
and an addition. x and t are stored as a row vector (that's how numpy stores
1-dimensional arrays), but the multiplication works as if x was a column vector
(to match linear algebra conventions):
transform_point_rt(rt, x) = transpose( matmult(R_from_r(rt[:3]), transpose(x)) +
transpose(rt[3,:]) ) =
= matmult(x, transpose(R_from_r(rt[:3]))) +
rt[3:]
By default this function returns the transformed points only. If we also want
gradients, pass get_gradients=True. Logic:
if not get_gradients: return u=rt(x)
else: return (u=rt(x),du/drt,du/dx)
This function supports broadcasting fully, so we can transform lots of points at
the same time and/or apply lots of different transformations at the same time
In-place operation is supported; the output array may be the same as the input
arrays to overwrite the input.
ARGUMENTS
- rt: array of shape (6,). This vector defines the transformation. rt[:3] is a
rotation defined as a Rodrigues vector; rt[3:] is a translation.
- x: array of shape (3,). The point being transformed
- get_gradients: optional boolean. By default (get_gradients=False) we return an
array of transformed points. Otherwise we return a tuple of arrays of
transformed points and their gradients.
- inverted: optional boolean, defaulting to False. If True, the opposite
transformation is computed. The gradient du/drt is returned in respect to the
input rt
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
If not get_gradients: we return an array of transformed point(s). Each
broadcasted slice has shape (3,)
If get_gradients: we return a tuple of arrays of transformed points and the
gradients (u=rt(x),du/drt,du/dx):
1. The transformed point(s). Each broadcasted slice has shape (3,)
2. The gradient du/drt. Each broadcasted slice has shape (3,6). The first
dimension selects the element of u, and the last dimension selects the
element of rt
3. The gradient du/dx. Each broadcasted slice has shape (3,3). The first
dimension selects the element of u, and the last dimension selects the
element of x
- triangulate(q, models, *, q_calibration_stdev=None, q_observation_stdev=None, q_observation_stdev_correlation=0, method=<function triangulate_leecivera_mid2 at 0x154cdbab60e0>, stabilize_coords=True)
- Triangulate N points with uncertainty propagation
SYNOPSIS
p, \
Var_p_calibration, \
Var_p_observation, \
Var_p_joint = \
mrcal.triangulate( nps.cat(q0, q),
(model0, model1),
q_calibration_stdev = q_calibration_stdev,
q_observation_stdev = q_observation_stdev,
q_observation_stdev_correlation = q_observation_stdev_correlation )
# p is now the triangulated point, in camera0 coordinates. The uncertainties
# of p from different sources are returned in the Var_p_... arrays
DESCRIPTION
This is the interface to the triangulation computations described in
http://mrcal.secretsauce.net/triangulation.html
Let's say two cameras observe a point p in space. The pixel observations of this
point in the two cameras are q0 and q1 respectively. If the two cameras are
calibrated (both intrinsics and extrinsics), I can reconstruct the observed
point p from the calibration and the two pixel observations. This is the
"triangulation" operation implemented by this function.
If the calibration and the pixel observations q0,q1 were perfect, computing the
corresponding point p would be trivial: unproject q0 and q1, and find the
intersection of the resulting rays. Since everything is perfect, the rays will
intersect exactly at p.
But in reality, both the calibration and the pixel observations are noisy. This
function propagates these sources of noise through the triangulation, to produce
covariance matrices of p.
Two kinds of noise are propagated:
- Calibration-time noise. This is the noise in the pixel observations of the
chessboard corners, propagated through the calibration to the triangulation
result. The normal use case is to calibrate once, and then use the same
calibration result many times. So each time we use a given calibration, we
have the same calibration-time noise, resulting in correlated errors between
each such triangulation operation. This is a source of bias: averaging many
different triangulation results will NOT push the errors to 0.
Here, only the calibration-time input noise is taken into account. Other
sources of calibration-time errors (bad input data, outliers, non-fitting
model) are ignored.
Furthermore, currently a vanilla calibration is assumed: both cameras in the
camera pair must have been calibrated together, and the cameras were not moved
in respect to each other after the calibration.
- Observation-time noise. This is the noise in the pixel observations of the
point being propagated: q0, q1. Unlike the calibration-time noise, each sample
of observations (q0,q1) IS independent from every other sample. So if we
observe the same point p many times, this observation noise will average out.
Both sources of noise are assumed normal with the noise on the x and y
components of the observation being independent. The standard deviation of the
noise is given by the q_calibration_stdev and q_observation_stdev arguments.
Since q0 and q1 often arise from an image correlation operation, they are
usually correlated with each other. It's not yet clear to me how to estimate
this correlation, but it can be specified in this function with the
q_observation_stdev_correlation argument:
- q_observation_stdev_correlation = 0: the noise on q0 and q1 is independent
- q_observation_stdev_correlation = 1: the noise on q0 and q1 is 100% correlated
The (q0x,q1x) and (q0y,q1y) cross terms of the covariance matrix are
(q_observation_stdev_correlation*q_observation_stdev)^2
Since the distribution of the calibration-time input noise is given at
calibration time, we can just use that distribution instead of specifying it
again: pass q_calibration_stdev<0 to do that.
COORDINATE STABILIZATION
We're analyzing the effects of calibration-time noise. As with projection
uncertainty, varying calibration-time noise affects the pose of the camera
coordinate system in respect to the physical camera housing. So Var(p) in the
camera coord system includes this coordinate-system fuzz, which is usually not
something we want to include. To compensate for this fuzz pass
stabilize_coords=True to return Var(p) in the physical camera housing coords.
The underlying method is exactly the same as how this is done with projection
uncertainty:
http://mrcal.secretsauce.net/uncertainty.html#propagating-through-projection
In the usual case, the translation component of this extra transformation is
negligible, but the rotation (even a small one) produces lateral uncertainty
that isn't really there. Enabling stabilization usually reduces the size of the
uncertainty ellipse in the lateral direction.
BROADCASTING
Broadcasting is fully supported on models and q. Each slice has 2 models and 2
pixel observations (q0,q1). If multiple models and/or observation pairs are
given, we compute the covariances with all the cross terms, so
Var_p_calibration.size grows quadratically with the number of broadcasted slices.
ARGUMENTS
- q: (..., 2,2) numpy array of pixel observations. Each broadcasted slice
describes a pixel observation from each of the two cameras
- models: iterable of shape (..., 2). Complex shapes may be represented in a
numpy array of dtype=np.object. Each row is two mrcal.cameramodel objects
describing the left and right cameras
- q_calibration_stdev: optional value describing the calibration-time noise. If
omitted or None, we do not compute or return the uncertainty resulting from
this noise. The noise in the observations of chessboard corners is assumed to
be normal and independent for each corner and for the x and y components. To
use the optimization residuals, pass any q_calibration_stdev < 0
- q_observation_stdev: optional value describing the observation-time noise. If
omitted or None, we do not compute or return the uncertainty resulting from
this noise. The noise in the observations is assumed to be normal and
independent for the x and y components
- q_observation_stdev_correlation: optional value, describing the correlation
between the pair of pixel coordinates observing the same point in space. Since
q0 and q1 often arise from an image correlation operation, they are usually
correlated with each other. This argument linearly scales q_observation_stdev:
0 = "independent", 1 = "100% correlated". The default is 0
- method: optional value selecting the triangulation method. This is one of the
mrcal.triangulate_... functions. If omitted, we select
mrcal.triangulate_leecivera_mid2. At this time, mrcal.triangulate_lindstrom is
usable only if we do not propagate any uncertainties
- stabilize_coords: optional boolean, defaulting to True. We always return the
triangulated point in camera-0 coordinates. If we're propagating
calibration-time noise, then the origin of those coordinates moves around
inside the housing of the camera. Characterizing this extra motion is
generally not desired in Var_p_calibration. To compensate for this motion, and
return Var_p_calibration in the coordinate system of the HOUSING of camera-0,
pass stabilize_coords = True.
RETURN VALUES
We always return p: the coordinates of the triangulated point(s) in the camera-0
coordinate system. Depending on the input arguments, we may also return
uncertainties. The general logic is:
if q_xxx_stdev is None:
don't propagate or return that source of uncertainty
if q_xxx_stdev == 0:
don't propagate that source of uncertainty, but return
Var_p_xxx = np.zeros(...)
if both q_xxx_stdev are not None:
we compute and report the two separate uncertainty components AND a
joint covariance combining the two
If we need to return Var_p_calibration, it has shape (...,3, ...,3) where ... is
the broadcasting shape. If a single triangulation is being performed, there's no
broadcasting, and Var_p_calibration.shape = (3,3). This representation allows us
to represent the correlated covariances (non-zero cross terms) that arise due to
calibration-time uncertainty.
If we need to return Var_p_observation, it has shape (...,3,3) where ... is the
broadcasting shape. If a single triangulation is being performed, there's no
broadcasting, and Var_p_observation.shape = (3,3). This representation is more
compact than that for Var_p_calibration because it assumes independent
covariances (zero cross terms) that result when propagating observation-time
uncertainty.
If we need to return Var_p_joint, it has shape (...,3, ...,3) where ... is the
broadcasting shape. If a single triangulation is being performed, there's no
broadcasting, and Var_p_joint.shape = (3,3). This representation allows us to
represent the correlated covariances (non-zero cross terms) that arise due to
calibration-time uncertainty.
Complete logic:
if q_calibration_stdev is None and
q_observation_stdev is None:
# p.shape = (...,3)
return p
if q_calibration_stdev is not None and
q_observation_stdev is None:
# p.shape = (...,3)
# Var_p_calibration.shape = (...,3,...,3)
return p, Var_p_calibration
if q_calibration_stdev is None and
q_observation_stdev is not None:
# p.shape = (...,3)
# Var_p_observation.shape = (...,3,3)
return p, Var_p_observation
if q_calibration_stdev is not None and
q_observation_stdev is not None:
# p.shape = (...,3)
# Var_p_calibration.shape = (...,3,...,3)
# Var_p_observation.shape = (...,3, 3)
# Var_p_joint.shape = (...,3,...,3)
return p, Var_p_calibration, Var_p_observation, Var_p_joint
- triangulate_geometric(v0, v1, t01=None, *, get_gradients=False, v_are_local=False, Rt01=None, out=None)
- Simple geometric triangulation
SYNOPSIS
models = ( mrcal.cameramodel('cam0.cameramodel'),
mrcal.cameramodel('cam1.cameramodel') )
images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1),
mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1))
Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(),
models[1].extrinsics_Rt_toref() )
R01 = Rt01[:3,:]
t01 = Rt01[ 3,:]
# pixel observation in camera0
q0 = np.array((1233, 2433), dtype=np.float32)
# corresponding pixel observation in camera1
q1, _ = \
mrcal.match_feature( *images,
q0 = q0,
template_size = (17,17),
method = cv2.TM_CCORR_NORMED,
search_radius = 20,
H10 = H10, # homography mapping q0 to q1
)
v0 = mrcal.unproject(q0, *models[0].intrinsics())
v1 = mrcal.rotate_point_R(R01, mrcal.unproject(q1, *models[1].intrinsics()))
# Estimated 3D position in camera-0 coordinates of the feature observed in
# the two cameras
p = mrcal.triangulate_geometric( v0, v1, t01 )
This is the lower-level triangulation routine. For a richer function that can be
used to propagate uncertainties, see mrcal.triangulate()
This function implements a very simple closest-approach-in-3D routine. It finds
the point on each ray that's nearest to the other ray, and returns the mean of
these two points. This is the "Mid" method in the paper
"Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera.
https://arxiv.org/abs/1907.11917
This paper compares many methods. This routine is simplest and fastest, but it
has the highest errors.
If the triangulated point lies behind either camera (i.e. if the observation
rays are parallel or divergent), (0,0,0) is returned.
This function supports broadcasting fully.
By default, this function takes a translation t01 instead of a full
transformation Rt01. This is consistent with most, but not all of the
triangulation routines. For API compatibility with ALL triangulation routines,
the full Rt01 may be passed as a kwarg.
Also, by default this function takes v1 in the camera-0-local coordinate system
like most, but not all the other triangulation routines. If v_are_local: then v1
is interpreted in the camera-1 coordinate system instead. This makes it simple
to compare the triangulation routines against one another.
The invocation compatible across all the triangulation routines omits t01, and
passes Rt01 and v_are_local:
triangulate_...( v0, v1,
Rt01 = Rt01,
v_are_local = False )
Gradient reporting is possible in the default case of Rt01 is None and not
v_are_local.
ARGUMENTS
- v0: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-0, described in the camera-0 coordinate
system
- v1: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-1, described in the camera-0 coordinate
system. Note that this vector is represented in the SAME coordinate system as
v0 in the default case (v_are_local is False)
- t01: (3,) numpy array containing the position of the camera-1 origin in the
camera-0 coordinate system. Exclusive with Rt01.
- get_gradients: optional boolean that defaults to False. Whether we should
compute and report the gradients. This affects what we return. If
get_gradients: v_are_local must have the default value
- v_are_local: optional boolean that defaults to False. If True: v1 is
represented in the local coordinate system of camera-1. The default is
consistent with most, but not all of the triangulation routines. Must have the
default value if get_gradients
- Rt01: optional (4,3) numpy array, defaulting to None. Exclusive with t01. If
given, we use this transformation from camera-1 coordinates to camera-0
coordinates instead of t01. If v_are_local: then Rt01 MUST be given instead of
t01. This exists for API compatibility with the other triangulation routines.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
if not get_gradients:
we return an (...,3) array of triangulated point positions in the camera-0
coordinate system
if get_gradients: we return a tuple:
- (...,3) array of triangulated point positions
- (...,3,3) array of the gradients of the triangulated positions in respect to
v0
- (...,3,3) array of the gradients of the triangulated positions in respect to
v1
- (...,3,3) array of the gradients of the triangulated positions in respect to
t01
- triangulate_leecivera_l1(v0, v1, t01=None, *, get_gradients=False, v_are_local=False, Rt01=None, out=None)
- Triangulation minimizing the L1-norm of angle differences
SYNOPSIS
models = ( mrcal.cameramodel('cam0.cameramodel'),
mrcal.cameramodel('cam1.cameramodel') )
images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1),
mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1))
Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(),
models[1].extrinsics_Rt_toref() )
R01 = Rt01[:3,:]
t01 = Rt01[ 3,:]
# pixel observation in camera0
q0 = np.array((1233, 2433), dtype=np.float32)
# corresponding pixel observation in camera1
q1, _ = \
mrcal.match_feature( *images,
q0 = q0,
template_size = (17,17),
method = cv2.TM_CCORR_NORMED,
search_radius = 20,
H10 = H10, # homography mapping q0 to q1
)
v0 = mrcal.unproject(q0, *models[0].intrinsics())
v1 = mrcal.rotate_point_R(R01, mrcal.unproject(q1, *models[1].intrinsics()))
# Estimated 3D position in camera-0 coordinates of the feature observed in
# the two cameras
p = mrcal.triangulate_leecivera_l1( v0, v1, t01 )
This is the lower-level triangulation routine. For a richer function that can be
used to propagate uncertainties, see mrcal.triangulate()
This function implements a triangulation routine minimizing the L1 norm of
angular errors. This is described in
"Closed-Form Optimal Two-View Triangulation Based on Angular Errors", Seong
Hun Lee and Javier Civera. ICCV 2019.
This is the "L1 ang" method in the paper
"Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera.
https://arxiv.org/abs/1907.11917
This paper compares many methods. This routine works decently well, but it isn't
the best. triangulate_leecivera_mid2() (or triangulate_leecivera_wmid2() if
we're near the cameras) are preferred, according to the paper.
If the triangulated point lies behind either camera (i.e. if the observation
rays are parallel or divergent), (0,0,0) is returned.
This function supports broadcasting fully.
By default, this function takes a translation t01 instead of a full
transformation Rt01. This is consistent with most, but not all of the
triangulation routines. For API compatibility with ALL triangulation routines,
the full Rt01 may be passed as a kwarg.
Also, by default this function takes v1 in the camera-0-local coordinate system
like most, but not all the other triangulation routines. If v_are_local: then v1
is interpreted in the camera-1 coordinate system instead. This makes it simple
to compare the triangulation routines against one another.
The invocation compatible across all the triangulation routines omits t01, and
passes Rt01 and v_are_local:
triangulate_...( v0, v1,
Rt01 = Rt01,
v_are_local = False )
Gradient reporting is possible in the default case of Rt01 is None and not
v_are_local.
ARGUMENTS
- v0: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-0, described in the camera-0 coordinate
system
- v1: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-1, described in the camera-0 coordinate
system. Note that this vector is represented in the SAME coordinate system as
v0 in the default case (v_are_local is False)
- t01: (3,) numpy array containing the position of the camera-1 origin in the
camera-0 coordinate system. Exclusive with Rt01.
- get_gradients: optional boolean that defaults to False. Whether we should
compute and report the gradients. This affects what we return. If
get_gradients: v_are_local must have the default value
- v_are_local: optional boolean that defaults to False. If True: v1 is
represented in the local coordinate system of camera-1. The default is
consistent with most, but not all of the triangulation routines. Must have the
default value if get_gradients
- Rt01: optional (4,3) numpy array, defaulting to None. Exclusive with t01. If
given, we use this transformation from camera-1 coordinates to camera-0
coordinates instead of t01. If v_are_local: then Rt01 MUST be given instead of
t01. This exists for API compatibility with the other triangulation routines.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
if not get_gradients:
we return an (...,3) array of triangulated point positions in the camera-0
coordinate system
if get_gradients: we return a tuple:
- (...,3) array of triangulated point positions
- (...,3,3) array of the gradients of the triangulated positions in respect to
v0
- (...,3,3) array of the gradients of the triangulated positions in respect to
v1
- (...,3,3) array of the gradients of the triangulated positions in respect to
t01
- triangulate_leecivera_linf(v0, v1, t01=None, *, get_gradients=False, v_are_local=False, Rt01=None, out=None)
- Triangulation minimizing the infinity-norm of angle differences
SYNOPSIS
models = ( mrcal.cameramodel('cam0.cameramodel'),
mrcal.cameramodel('cam1.cameramodel') )
images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1),
mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1))
Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(),
models[1].extrinsics_Rt_toref() )
R01 = Rt01[:3,:]
t01 = Rt01[ 3,:]
# pixel observation in camera0
q0 = np.array((1233, 2433), dtype=np.float32)
# corresponding pixel observation in camera1
q1, _ = \
mrcal.match_feature( *images,
q0 = q0,
template_size = (17,17),
method = cv2.TM_CCORR_NORMED,
search_radius = 20,
H10 = H10, # homography mapping q0 to q1
)
v0 = mrcal.unproject(q0, *models[0].intrinsics())
v1 = mrcal.rotate_point_R(R01, mrcal.unproject(q1, *models[1].intrinsics()))
# Estimated 3D position in camera-0 coordinates of the feature observed in
# the two cameras
p = mrcal.triangulate_leecivera_linf( v0, v1, t01 )
This is the lower-level triangulation routine. For a richer function that can be
used to propagate uncertainties, see mrcal.triangulate()
This function implements a triangulation routine minimizing the infinity norm of
angular errors (it minimizes the larger of the two angle errors). This is
described in
"Closed-Form Optimal Two-View Triangulation Based on Angular Errors", Seong
Hun Lee and Javier Civera. ICCV 2019.
This is the "L-infinity ang" method in the paper
"Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera.
https://arxiv.org/abs/1907.11917
This paper compares many methods. This routine works decently well, but it isn't
the best. triangulate_leecivera_mid2() (or triangulate_leecivera_wmid2() if
we're near the cameras) are preferred, according to the paper.
If the triangulated point lies behind either camera (i.e. if the observation
rays are parallel or divergent), (0,0,0) is returned.
This function supports broadcasting fully.
By default, this function takes a translation t01 instead of a full
transformation Rt01. This is consistent with most, but not all of the
triangulation routines. For API compatibility with ALL triangulation routines,
the full Rt01 may be passed as a kwarg.
Also, by default this function takes v1 in the camera-0-local coordinate system
like most, but not all the other triangulation routines. If v_are_local: then v1
is interpreted in the camera-1 coordinate system instead. This makes it simple
to compare the triangulation routines against one another.
The invocation compatible across all the triangulation routines omits t01, and
passes Rt01 and v_are_local:
triangulate_...( v0, v1,
Rt01 = Rt01,
v_are_local = False )
Gradient reporting is possible in the default case of Rt01 is None and not
v_are_local.
ARGUMENTS
- v0: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-0, described in the camera-0 coordinate
system
- v1: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-1, described in the camera-0 coordinate
system. Note that this vector is represented in the SAME coordinate system as
v0 in the default case (v_are_local is False)
- t01: (3,) numpy array containing the position of the camera-1 origin in the
camera-0 coordinate system. Exclusive with Rt01.
- get_gradients: optional boolean that defaults to False. Whether we should
compute and report the gradients. This affects what we return. If
get_gradients: v_are_local must have the default value
- v_are_local: optional boolean that defaults to False. If True: v1 is
represented in the local coordinate system of camera-1. The default is
consistent with most, but not all of the triangulation routines. Must have the
default value if get_gradients
- Rt01: optional (4,3) numpy array, defaulting to None. Exclusive with t01. If
given, we use this transformation from camera-1 coordinates to camera-0
coordinates instead of t01. If v_are_local: then Rt01 MUST be given instead of
t01. This exists for API compatibility with the other triangulation routines.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
if not get_gradients:
we return an (...,3) array of triangulated point positions in the camera-0
coordinate system
if get_gradients: we return a tuple:
- (...,3) array of triangulated point positions
- (...,3,3) array of the gradients of the triangulated positions in respect to
v0
- (...,3,3) array of the gradients of the triangulated positions in respect to
v1
- (...,3,3) array of the gradients of the triangulated positions in respect to
t01
- triangulate_leecivera_mid2(v0, v1, t01=None, *, get_gradients=False, v_are_local=False, Rt01=None, out=None)
- Triangulation using Lee and Civera's alternative midpoint method
SYNOPSIS
models = ( mrcal.cameramodel('cam0.cameramodel'),
mrcal.cameramodel('cam1.cameramodel') )
images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1),
mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1))
Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(),
models[1].extrinsics_Rt_toref() )
R01 = Rt01[:3,:]
t01 = Rt01[ 3,:]
# pixel observation in camera0
q0 = np.array((1233, 2433), dtype=np.float32)
# corresponding pixel observation in camera1
q1, _ = \
mrcal.match_feature( *images,
q0 = q0,
template_size = (17,17),
method = cv2.TM_CCORR_NORMED,
search_radius = 20,
H10 = H10, # homography mapping q0 to q1
)
v0 = mrcal.unproject(q0, *models[0].intrinsics())
v1 = mrcal.rotate_point_R(R01, mrcal.unproject(q1, *models[1].intrinsics()))
# Estimated 3D position in camera-0 coordinates of the feature observed in
# the two cameras
p = mrcal.triangulate_leecivera_mid2( v0, v1, t01 )
This is the lower-level triangulation routine. For a richer function that can be
used to propagate uncertainties, see mrcal.triangulate()
This function implements the "Mid2" triangulation routine in
"Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera.
https://arxiv.org/abs/1907.11917
This paper compares many methods. This routine works decently well, but it isn't
the best. The method in this function should be a good tradeoff between accuracy
(in 3D and 2D) and performance. If we're looking at objects very close to the
cameras, where the distances to the two cameras are significantly different, use
triangulate_leecivera_wmid2() instead.
If the triangulated point lies behind either camera (i.e. if the observation
rays are parallel or divergent), (0,0,0) is returned.
This function supports broadcasting fully.
By default, this function takes a translation t01 instead of a full
transformation Rt01. This is consistent with most, but not all of the
triangulation routines. For API compatibility with ALL triangulation routines,
the full Rt01 may be passed as a kwarg.
Also, by default this function takes v1 in the camera-0-local coordinate system
like most, but not all the other triangulation routines. If v_are_local: then v1
is interpreted in the camera-1 coordinate system instead. This makes it simple
to compare the triangulation routines against one another.
The invocation compatible across all the triangulation routines omits t01, and
passes Rt01 and v_are_local:
triangulate_...( v0, v1,
Rt01 = Rt01,
v_are_local = False )
Gradient reporting is possible in the default case of Rt01 is None and not
v_are_local.
ARGUMENTS
- v0: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-0, described in the camera-0 coordinate
system
- v1: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-1, described in the camera-0 coordinate
system. Note that this vector is represented in the SAME coordinate system as
v0 in the default case (v_are_local is False)
- t01: (3,) numpy array containing the position of the camera-1 origin in the
camera-0 coordinate system. Exclusive with Rt01.
- get_gradients: optional boolean that defaults to False. Whether we should
compute and report the gradients. This affects what we return. If
get_gradients: v_are_local must have the default value
- v_are_local: optional boolean that defaults to False. If True: v1 is
represented in the local coordinate system of camera-1. The default is
consistent with most, but not all of the triangulation routines. Must have the
default value if get_gradients
- Rt01: optional (4,3) numpy array, defaulting to None. Exclusive with t01. If
given, we use this transformation from camera-1 coordinates to camera-0
coordinates instead of t01. If v_are_local: then Rt01 MUST be given instead of
t01. This exists for API compatibility with the other triangulation routines.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
if not get_gradients:
we return an (...,3) array of triangulated point positions in the camera-0
coordinate system
if get_gradients: we return a tuple:
- (...,3) array of triangulated point positions
- (...,3,3) array of the gradients of the triangulated positions in respect to
v0
- (...,3,3) array of the gradients of the triangulated positions in respect to
v1
- (...,3,3) array of the gradients of the triangulated positions in respect to
t01
- triangulate_leecivera_wmid2(v0, v1, t01=None, *, get_gradients=False, v_are_local=False, Rt01=None, out=None)
- Triangulation using Lee and Civera's weighted alternative midpoint method
SYNOPSIS
models = ( mrcal.cameramodel('cam0.cameramodel'),
mrcal.cameramodel('cam1.cameramodel') )
images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1),
mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1))
Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(),
models[1].extrinsics_Rt_toref() )
R01 = Rt01[:3,:]
t01 = Rt01[ 3,:]
# pixel observation in camera0
q0 = np.array((1233, 2433), dtype=np.float32)
# corresponding pixel observation in camera1
q1, _ = \
mrcal.match_feature( *images,
q0 = q0,
template_size = (17,17),
method = cv2.TM_CCORR_NORMED,
search_radius = 20,
H10 = H10, # homography mapping q0 to q1
)
v0 = mrcal.unproject(q0, *models[0].intrinsics())
v1 = mrcal.rotate_point_R(R01, mrcal.unproject(q1, *models[1].intrinsics()))
# Estimated 3D position in camera-0 coordinates of the feature observed in
# the two cameras
p = mrcal.triangulate_leecivera_wmid2( v0, v1, t01 )
This is the lower-level triangulation routine. For a richer function that can be
used to propagate uncertainties, see mrcal.triangulate()
This function implements the "wMid2" triangulation routine in
"Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera.
https://arxiv.org/abs/1907.11917
This paper compares many methods. This routine works decently well, but it isn't
the best. The preferred method, according to the paper, is
triangulate_leecivera_mid2. THIS method (wMid2) is better if we're looking at
objects very close to the cameras, where the distances to the two cameras are
significantly different.
If the triangulated point lies behind either camera (i.e. if the observation
rays are parallel or divergent), (0,0,0) is returned.
This function supports broadcasting fully.
By default, this function takes a translation t01 instead of a full
transformation Rt01. This is consistent with most, but not all of the
triangulation routines. For API compatibility with ALL triangulation routines,
the full Rt01 may be passed as a kwarg.
Also, by default this function takes v1 in the camera-0-local coordinate system
like most, but not all the other triangulation routines. If v_are_local: then v1
is interpreted in the camera-1 coordinate system instead. This makes it simple
to compare the triangulation routines against one another.
The invocation compatible across all the triangulation routines omits t01, and
passes Rt01 and v_are_local:
triangulate_...( v0, v1,
Rt01 = Rt01,
v_are_local = False )
Gradient reporting is possible in the default case of Rt01 is None and not
v_are_local.
ARGUMENTS
- v0: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-0, described in the camera-0 coordinate
system
- v1: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-1, described in the camera-0 coordinate
system. Note that this vector is represented in the SAME coordinate system as
v0 in the default case (v_are_local is False)
- t01: (3,) numpy array containing the position of the camera-1 origin in the
camera-0 coordinate system. Exclusive with Rt01.
- get_gradients: optional boolean that defaults to False. Whether we should
compute and report the gradients. This affects what we return. If
get_gradients: v_are_local must have the default value
- v_are_local: optional boolean that defaults to False. If True: v1 is
represented in the local coordinate system of camera-1. The default is
consistent with most, but not all of the triangulation routines. Must have the
default value if get_gradients
- Rt01: optional (4,3) numpy array, defaulting to None. Exclusive with t01. If
given, we use this transformation from camera-1 coordinates to camera-0
coordinates instead of t01. If v_are_local: then Rt01 MUST be given instead of
t01. This exists for API compatibility with the other triangulation routines.
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
if not get_gradients:
we return an (...,3) array of triangulated point positions in the camera-0
coordinate system
if get_gradients: we return a tuple:
- (...,3) array of triangulated point positions
- (...,3,3) array of the gradients of the triangulated positions in respect to
v0
- (...,3,3) array of the gradients of the triangulated positions in respect to
v1
- (...,3,3) array of the gradients of the triangulated positions in respect to
t01
- triangulate_lindstrom(v0, v1, Rt01, *, get_gradients=False, v_are_local=True, out=None)
- Triangulation minimizing the 2-norm of pinhole reprojection errors
SYNOPSIS
models = ( mrcal.cameramodel('cam0.cameramodel'),
mrcal.cameramodel('cam1.cameramodel') )
images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1),
mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1))
Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(),
models[1].extrinsics_Rt_toref() )
R01 = Rt01[:3,:]
t01 = Rt01[ 3,:]
# pixel observation in camera0
q0 = np.array((1233, 2433), dtype=np.float32)
# corresponding pixel observation in camera1
q1, _ = \
mrcal.match_feature( *images,
q0 = q0,
template_size = (17,17),
method = cv2.TM_CCORR_NORMED,
search_radius = 20,
H10 = H10, # homography mapping q0 to q1
)
# observation vectors in the LOCAL coordinate system of the two cameras
v0 = mrcal.unproject(q0, *models[0].intrinsics())
v1 = mrcal.unproject(q1, *models[1].intrinsics())
# Estimated 3D position in camera-0 coordinates of the feature observed in
# the two cameras
p = mrcal.triangulate_lindstrom( v0, v1, Rt01 = Rt01 )
This is the lower-level triangulation routine. For a richer function that can be
used to propagate uncertainties, see mrcal.triangulate()
This function implements a triangulation routine minimizing the 2-norm of
reprojection errors, ASSUMING a pinhole projection. This is described in
"Triangulation Made Easy", Peter Lindstrom, IEEE Conference on Computer Vision
and Pattern Recognition, 2010.
This is the "L2 img 5-iteration" method in the paper
"Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera.
https://arxiv.org/abs/1907.11917
but with only 2 iterations (Lindstrom's paper recommends 2 iterations). This
Lee, Civera paper compares many methods. This routine works decently well, but
it isn't the best. The angular methods should work better than this one for wide
lenses. triangulate_leecivera_mid2() (or triangulate_leecivera_wmid2() if we're
near the cameras) are preferred, according to the paper.
The assumption of a pinhole projection is a poor one when using a wide lens, and
looking away from the optical center. The Lee-Civera triangulation functions
don't have this problem, and are generally faster. See the Lee, Civera paper for
details.
If the triangulated point lies behind either camera (i.e. if the observation
rays are parallel or divergent), (0,0,0) is returned.
This function supports broadcasting fully.
This function takes a full transformation Rt01, instead of t01 like most of the
other triangulation functions do by default. The other function may take Rt01,
for API compatibility.
Also, by default this function takes v1 in the camera-1-local coordinate system
unlike most of the other triangulation routines. If not v_are_local: then v1 is
interpreted in the camera-0 coordinate system instead. This makes it simple to
compare the routines against one another.
The invocation compatible across all the triangulation routines omits t01, and
passes Rt01 and v_are_local:
triangulate_...( v0, v1,
Rt01 = Rt01,
v_are_local = False )
Gradient reporting is possible in the default case of v_are_local is True
ARGUMENTS
- v0: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-0, described in the camera-0 coordinate
system
- v1: (3,) numpy array containing a not-necessarily-normalized observation
vector of a feature observed in camera-1, described in the camera-1 coordinate
system by default (v_are_local is True). Note that this vector is represented
in the camera-local coordinate system, unlike the representation in all the
other triangulation routines
- Rt01: (4,3) numpy array describing the transformation from camera-1
coordinates to camera-0 coordinates
- get_gradients: optional boolean that defaults to False. Whether we should
compute and report the gradients. This affects what we return. If
get_gradients: v_are_local must have the default value
- v_are_local: optional boolean that defaults to True. If True: v1 is
represented in the local coordinate system of camera-1. This is different from
the other triangulation routines. Set v_are_local to False to make this
function interpret v1 similarly to the other triangulation routines. Must have
the default value if get_gradients
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing (and
possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not
get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is
a tuple of all the output numpy arrays. If 'out' is given, we return the 'out'
that was passed in. This is the standard behavior provided by
numpysane_pywrap.
RETURNED VALUE
if not get_gradients:
we return an (...,3) array of triangulated point positions in the camera-0
coordinate system
if get_gradients: we return a tuple:
- (...,3) array of triangulated point positions
- (...,3,3) array of the gradients of the triangulated positions in respect to
v0
- (...,3,3) array of the gradients of the triangulated positions in respect to
v1
- (...,3,4,3) array of the gradients of the triangulated positions in respect
to Rt01
- unpack_state(...)
- Scales a state vector from the packed, unitless form used by the optimizer
SYNOPSIS
m = mrcal.cameramodel('xxx.cameramodel')
optimization_inputs = m.optimization_inputs()
b_packed = mrcal.optimizer_callback(**optimization_inputs)[0]
b = b_packed.copy()
mrcal.unpack_state(b, **optimization_inputs)
In order to make the optimization well-behaved, we scale all the variables in
the state and the gradients before passing them to the optimizer. The internal
optimization library thus works only with unitless (or "packed") data.
This function takes a packed numpy array of shape (...., Nstate), and scales it
to produce full data with real units. This function applies the scaling directly
to the input array; the input is modified, and nothing is returned.
To unpack a state vector, you naturally call unpack_state(). To unpack a
jacobian matrix, you would call pack_state() because in a jacobian, the state is
in the denominator.
Broadcasting is supported: any leading dimensions will be processed correctly,
as long as the given array has shape (..., Nstate).
In order to know what the scale factors should be, and how they should map to
each variable in the state vector, we need quite a bit of context. If we have
the full set of inputs to the optimization function, we can pass in those (as
shown in the example above). Or we can pass the individual arguments that are
needed (see ARGUMENTS section for the full list). If the optimization inputs and
explicitly-given arguments conflict about the size of some array, the explicit
arguments take precedence. If any array size is not specified, it is assumed to
be 0. Thus most arguments are optional.
ARGUMENTS
- b: a numpy array of shape (..., Nstate). This is the packed state on input,
and the full state on output. The input array is modified.
- **kwargs: if the optimization inputs are available, they can be passed-in as
kwargs. These inputs contain everything this function needs to operate. If we
don't have these, then the rest of the variables will need to be given
- lensmodel: string specifying the lensmodel we're using (this is always
'LENSMODEL_...'). The full list of valid models is returned by
mrcal.supported_lensmodels(). This is required if we're not passing in the
optimization inputs
- do_optimize_intrinsics_core
do_optimize_intrinsics_distortions
do_optimize_extrinsics
do_optimize_calobject_warp
do_optimize_frames
optional booleans; default to True. These specify what we're optimizing. See
the documentation for mrcal.optimize() for details
- Ncameras_intrinsics
Ncameras_extrinsics
Nframes
Npoints
Npoints_fixed
optional integers; default to 0. These specify the sizes of various arrays in
the optimization. See the documentation for mrcal.optimize() for details
RETURNED VALUE
None. The scaling is applied to the input array
- unproject(q, lensmodel, intrinsics_data, *, normalize=False, get_gradients=False, out=None)
- Unprojects pixel coordinates to observation vectors
SYNOPSIS
# q is a (...,2) array of pixel observations
v = mrcal.unproject( q,
lensmodel, intrinsics_data )
### OR ###
m = mrcal.cameramodel(...)
v = mrcal.unproject( q, *m.intrinsics() )
Maps a set of 2D imager points q to a set of 3D vectors in camera coordinates
that produced these pixel observations. Each 3D vector is unique only
up-to-length, and the returned vectors aren't normalized by default. The default
length of the returned vector is arbitrary, and selected for the convenience of
the implementation. Pass normalize=True to always return unit vectors.
This is the "reverse" direction, so an iterative nonlinear optimization is
performed internally to compute this result. This is much slower than
mrcal_project. For OpenCV distortions specifically, OpenCV has
cvUndistortPoints() (and cv2.undistortPoints()), but these are inaccurate and we
do not use them: https://github.com/opencv/opencv/issues/8811
Gradients are available by passing get_gradients=True. Since unproject() is
implemented as an iterative solve around project(), the unproject() gradients
are computed by manipulating the gradients reported by project() at the
solution. The reported gradients are relative to whatever unproject() is
reporting; the unprojection is unique only up-to-length, and the magnitude isn't
fixed. So the gradients may include a component in the direction of the returned
observation vector: this follows the arbitrary scaling used by unproject(). It
is possible to pass normalize=True; we then return NORMALIZED observation
vectors and the gradients of those NORMALIZED vectors. In that case, those
gradients are guaranteed to be orthogonal to the observation vector. The vector
normalization involves a bit more computation, so it isn't the default.
NOTE: THE MAGNITUDE OF THE RETURNED VECTOR CHANGES IF get_gradients CHANGES. The
reported gradients are correct relative to the output returned with
get_gradients=True. Passing normalize=True can be used to smooth this out:
unproject(..., normalize=True)
returns the same vectors as
unproject(..., normalize=True, get_gradients=True)[0]
Broadcasting is fully supported across q and intrinsics_data.
Models that have no gradients available cannot use mrcal_unproject() in C, but
CAN still use this mrcal.unproject() Python routine: a slower routine is
employed that uses numerical differences instead of analytical gradients.
ARGUMENTS
- q: array of dims (...,2); the pixel coordinates we're unprojecting
- lensmodel: a string such as
LENSMODEL_PINHOLE
LENSMODEL_OPENCV4
LENSMODEL_CAHVOR
LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=12_fov_x_deg=100
- intrinsics_data: array of dims (Nintrinsics):
(focal_x, focal_y, center_pixel_x, center_pixel_y, distortion0, distortion1,
...)
The focal lengths are given in pixels.
- normalize: optional boolean defaults to False. If True: normalize the output
vectors
- get_gradients: optional boolean that defaults to False. Whether we should
compute and report the gradients. This affects what we return (see below). If
not normalize, the magnitude of the reported vectors changes if get_gradients
is turned on/off (see above)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing arrays,
specify them with the 'out' kwarg. If not get_gradients: 'out' is the one
numpy array we will write into. Else: 'out' is a tuple of all the output numpy
arrays. If 'out' is given, we return the same arrays passed in. This is the
standard behavior provided by numpysane_pywrap.
RETURNED VALUE
if not get_gradients:
we return an (...,3) array of unprojected observation vectors. Not normalized
by default; see description above
if get_gradients: we return a tuple:
- (...,3) array of unprojected observation vectors
- (...,3,2) array of gradients of unprojected observation vectors in respect
to pixel coordinates
- (...,3,Nintrinsics) array of gradients of unprojected observation vectors in
respect to the intrinsics
- unproject_latlon(points, fxycxy=array([1., 1., 0., 0.]), *, get_gradients=False, out=None)
- Unprojects 2D pixel coordinates using a transverse equirectangular projection
SYNOPSIS
# points is a (N,2) array of imager points
v = mrcal.unproject_latlon( points, fxycxy )
# v is now a (N,3) array of observation directions in the camera coordinate
# system. v are normalized
This is a special case of mrcal.unproject(). Useful not for representing lenses,
but for performing stereo rectification. Lenses do not follow this model. See
the lensmodel documentation for details:
http://mrcal.secretsauce.net/lensmodels.html#lensmodel-latlon
Given a (N,2) array of transverse equirectangular coordinates and the parameters
fxycxy, this function computes the inverse projection, optionally with
gradients.
The vectors returned by this function are normalized.
ARGUMENTS
- points: array of dims (...,2); the transverse equirectangular coordinates
we're unprojecting. This supports broadcasting fully, and any leading
dimensions are allowed, including none
- fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy),
with all elements given in units of pixels. fx and fy are the horizontal and
vertical focal lengths, respectively. (cx,cy) are pixel coordinates
corresponding to the projection of p = [0,0,1]. If omitted, default values are
used to specify a normalized transverse equirectangular projection : fx=fy=1.0
and cx=cy=0.0. This produces q = (lat,lon)
- get_gradients: optional boolean, defaults to False. This affects what we
return (see below)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing arrays,
specify them with the 'out' kwarg. If not get_gradients: 'out' is the one
numpy array we will write into. Else: 'out' is a tuple of all the output numpy
arrays. If 'out' is given, we return the same arrays passed in. This is the
standard behavior provided by numpysane_pywrap.
RETURNED VALUE
if not get_gradients: we return an (...,3) array of unprojected observation
vectors. These are normalized.
if get_gradients: we return a tuple:
- (...,3) array of unprojected observation vectors. These are normalized.
- (...,3,2) array of the gradients of the observation vectors in respect to
the input 2D transverse equirectangular coordinates
- unproject_lonlat(points, fxycxy=array([1., 1., 0., 0.]), *, get_gradients=False, out=None)
- Unprojects a set of 2D pixel coordinates using an equirectangular projection
SYNOPSIS
# points is a (N,2) array of imager points
v = mrcal.unproject_lonlat( points, fxycxy )
# v is now a (N,3) array of observation directions in the camera coordinate
# system. v are normalized
This is a special case of mrcal.unproject(). Useful not for
representing lenses, but for describing the projection function of wide
panoramic images. Lenses do not follow this model. See the lensmodel
documentation for details:
http://mrcal.secretsauce.net/lensmodels.html#lensmodel-lonlat
Given a (N,2) array of equirectangular coordinates and the parameters fxycxy,
this function computes the inverse projection, optionally with gradients.
The vectors returned by this function are normalized.
ARGUMENTS
- points: array of dims (...,2); the equirectangular coordinates we're
unprojecting. This supports broadcasting fully, and any leading dimensions are
allowed, including none
- fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy). fx
and fy are the "focal lengths": they specify the angular resolution of the
image, in pixels/radian. (cx,cy) are pixel coordinates corresponding to the
projection of p = [0,0,1]. If omitted, default values are used to specify a
normalized equirectangular projection : fx=fy=1.0 and cx=cy=0.0. This produces
q = (lon,lat)
- get_gradients: optional boolean, defaults to False. This affects what we
return (see below)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing arrays,
specify them with the 'out' kwarg. If not get_gradients: 'out' is the one
numpy array we will write into. Else: 'out' is a tuple of all the output numpy
arrays. If 'out' is given, we return the same arrays passed in. This is the
standard behavior provided by numpysane_pywrap.
RETURNED VALUE
if not get_gradients: we return an (...,3) array of unprojected observation
vectors. These are normalized.
if get_gradients: we return a tuple:
- (...,3) array of unprojected observation vectors. These are normalized.
- (...,3,2) array of the gradients of the observation vectors in respect to
the input 2D equirectangular coordinates
- unproject_pinhole(points, fxycxy=array([1., 1., 0., 0.]), *, get_gradients=False, out=None)
- Unprojects 2D pixel coordinates using a pinhole projection
SYNOPSIS
# points is a (N,2) array of imager points
v = mrcal.unproject_pinhole( points,
fxycxy )
# v is now a (N,3) array of observation directions in the camera coordinate
# system. v are NOT normalized
This is a special case of mrcal.unproject(). Useful to represent a very simple,
very perfect lens. Wide lenses do not follow this model. Long lenses usually
more-or-less DO follow this model. See the lensmodel documentation for details:
http://mrcal.secretsauce.net/lensmodels.html#lensmodel-pinhole
Given a (N,2) array of pinhole coordinates and the parameters fxycxy, this
function computes the inverse projection, optionally with gradients.
The vectors returned by this function are NOT normalized.
ARGUMENTS
- points: array of dims (...,2); the pinhole coordinates
we're unprojecting. This supports broadcasting fully, and any leading
dimensions are allowed, including none
- fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy),
with all elements given in units of pixels. fx and fy are the horizontal and
vertical focal lengths, respectively. (cx,cy) are pixel coordinates
corresponding to the projection of p = [0,0,1]. If omitted, default values are
used: fx=fy=1.0 and cx=cy=0.0.
- get_gradients: optional boolean, defaults to False. This affects what we
return (see below)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing arrays,
specify them with the 'out' kwarg. If not get_gradients: 'out' is the one
numpy array we will write into. Else: 'out' is a tuple of all the output numpy
arrays. If 'out' is given, we return the same arrays passed in. This is the
standard behavior provided by numpysane_pywrap.
RETURNED VALUE
if not get_gradients: we return an (...,3) array of unprojected observation
vectors. These are NOT normalized.
if get_gradients: we return a tuple:
- (...,3) array of unprojected observation vectors. These are NOT normalized.
- (...,3,2) array of the gradients of the observation vectors in respect to
the input 2D pinhole coordinates
- unproject_stereographic(points, fxycxy=array([1., 1., 0., 0.]), *, get_gradients=False, out=None)
- Unprojects a set of 2D pixel coordinates using a stereographic model
SYNOPSIS
# points is a (N,2) array of pixel coordinates
v = mrcal.unproject_stereographic( points, fxycxy)
# v is now a (N,3) array of observation directions in the camera coordinate
# system. v are NOT normalized
This is a special case of mrcal.unproject(). No actual lens ever follows this
model exactly, but this is useful as a baseline for other models. See the
lensmodel documentation for details:
http://mrcal.secretsauce.net/lensmodels.html#lensmodel-stereographic
Given a (N,2) array of stereographic coordinates and parameters of a perfect
stereographic camera, this function computes the inverse projection, optionally
with gradients.
The user can pass in focal length and center-pixel values. Or they can be
omitted to compute a "normalized" stereographic projection (fx = fy = 1, cx = cy
= 0).
The stereographic projection is able to represent points behind the camera, and
has only one singular observation direction: directly behind the camera, along
the optical axis.
This projection acts radially. If the observation vector v makes an angle theta
with the optical axis, then the projected point q is 2 tan(theta/2) f from the
image center.
ARGUMENTS
- points: array of dims (...,2); the stereographic coordinates we're
unprojecting. This supports broadcasting fully, and any leading dimensions are
allowed, including none
- fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy),
with all elements given in units of pixels. fx and fy are the horizontal and
vertical focal lengths, respectively. (cx,cy) are pixel coordinates
corresponding to the projection of p = [0,0,1]. If omitted, default values are
used to specify a normalized stereographic projection : fx=fy=1.0 and
cx=cy=0.0.
- get_gradients: optional boolean, defaults to False. This affects what we
return (see below)
- out: optional argument specifying the destination. By default, new numpy
array(s) are created and returned. To write the results into existing arrays,
specify them with the 'out' kwarg. If not get_gradients: 'out' is the one
numpy array we will write into. Else: 'out' is a tuple of all the output numpy
arrays. If 'out' is given, we return the same arrays passed in. This is the
standard behavior provided by numpysane_pywrap.
RETURNED VALUE
if not get_gradients: we return an (...,3) array of unprojected observation
vectors. These are NOT normalized.
if get_gradients: we return a tuple:
- (...,3) array of unprojected observation vectors. These are NOT normalized.
- (...,3,2) array of the gradients of the observation vectors in respect to
the input 2D stereographic coordinates
- worst_direction_stdev(cov)
- Compute the worst-direction standard deviation from a 2x2 covariance matrix
SYNOPSIS
# A covariance matrix
print(cov)
===>
[[ 1. -0.4]
[-0.4 0.5]]
# Sample 1000 0-mean points using this covariance
x = np.random.multivariate_normal(mean = np.array((0,0)),
cov = cov,
size = (1000,))
# Compute the worst-direction standard deviation of the sampled data
print(np.sqrt(np.max(np.linalg.eig(np.mean(nps.outer(x,x),axis=0))[0])))
===>
1.1102510878087053
# The predicted worst-direction standard deviation
print(mrcal.worst_direction_stdev(cov))
===> 1.105304960905736
The covariance of a (2,) random variable can be described by a (2,2)
positive-definite symmetric matrix. The 1-sigma contour of this random variable
is described by an ellipse with its axes aligned with the eigenvectors of the
covariance, and the semi-major and semi-minor axis lengths specified as the sqrt
of the corresponding eigenvalues. This function returns the worst-case standard
deviation of the given covariance: the sqrt of the larger of the two
eigenvalues.
This function supports broadcasting fully.
DERIVATION
Let cov = (a b). If l is an eigenvalue of the covariance then
(b c)
(a-l)*(c-l) - b^2 = 0 --> l^2 - (a+c) l + ac-b^2 = 0
--> l = (a+c +- sqrt( a^2 + 2ac + c^2 - 4ac + 4b^2)) / 2 =
= (a+c +- sqrt( a^2 - 2ac + c^2 + 4b^2)) / 2 =
= (a+c)/2 +- sqrt( (a-c)^2/4 + b^2)
So the worst-direction standard deviation is
sqrt((a+c)/2 + sqrt( (a-c)^2/4 + b^2))
ARGUMENTS
- cov: the covariance matrices given as a (..., 2,2) array. Valid covariances
are positive-semi-definite (symmetric with eigenvalues >= 0), but this is not
checked
RETURNED VALUES
The worst-direction standard deviation. This is a scalar or an array, if we're
broadcasting
|