示例#1
0
def _noisy_observation_vectors_for_triangulation(p, Rt01, intrinsics0,
                                                 intrinsics1, Nsamples, sigma):

    # p has shape (...,3)

    # shape (..., 2)
    q0 = mrcal.project(p, *intrinsics0)
    q1 = mrcal.project(mrcal.transform_point_Rt(mrcal.invert_Rt(Rt01), p),
                       *intrinsics1)

    # shape (..., 1,2). Each has x,y
    q0 = nps.dummy(q0, -2)
    q1 = nps.dummy(q1, -2)

    q_noise = np.random.randn(*p.shape[:-1], Nsamples, 2, 2) * sigma
    # shape (..., Nsamples,2). Each has x,y
    q0_noise = q_noise[..., :, 0, :]
    q1_noise = q_noise[..., :, 1, :]

    q0_noisy = q0 + q0_noise
    q1_noisy = q1 + q1_noise

    # shape (..., Nsamples, 3)
    v0local_noisy = mrcal.unproject(q0_noisy, *intrinsics0)
    v1local_noisy = mrcal.unproject(q1_noisy, *intrinsics1)
    v0_noisy = v0local_noisy
    v1_noisy = mrcal.rotate_point_R(Rt01[:3, :], v1local_noisy)

    # All have shape (..., Nsamples,3)
    return \
        v0local_noisy, v1local_noisy, v0_noisy,v1_noisy, \
        q0,q1, q0_noisy, q1_noisy
示例#2
0
def callback_l2_reprojection(p, v0local, v1local, Rt01):
    dq0 = \
        mrcal.project(p,       *model0.intrinsics()) - \
        mrcal.project(v0local, *model0.intrinsics())
    dq1 = \
        mrcal.project(mrcal.transform_point_Rt(mrcal.invert_Rt(Rt01),p),
                      *model1.intrinsics()) - \
        mrcal.project(v1local, *model1.intrinsics())
    return nps.norm2(dq0) + nps.norm2(dq1)
示例#3
0
    def _extrinsics_Rt(self, toref, Rt=None):
        r'''Get or set the extrinsics in this model

        This function represents the pose as a shape (4,3) numpy array that
        contains a (3,3) rotation matrix, followed by a (1,3) translation in the
        last row:

          R = Rt[:3,:]
          t = Rt[ 3,:]

        The transformation is b <-- R*a + t:

          import numpysane as nps
          b = nps.matmult(a, nps.transpose(R)) + t

        if Rt is None: this is a getter; otherwise a setter.

        toref is a boolean. if toref: then Rt maps points in the coord system of
        THIS camera to the reference coord system. Otherwise in the opposite
        direction

        '''

        # The internal representation is rt_fromref

        if Rt is None:
            # getter
            rt_fromref = self._extrinsics
            Rt_fromref = mrcal.Rt_from_rt(rt_fromref)
            if not toref:
                return Rt_fromref
            return mrcal.invert_Rt(Rt_fromref)

        # setter
        if toref:
            Rt_fromref = mrcal.invert_Rt(Rt)
            self._extrinsics = mrcal.rt_from_Rt(Rt_fromref)
            return True

        self._extrinsics = mrcal.rt_from_Rt(Rt)
        return True
示例#4
0
def test_geometry(Rt01,
                  p,
                  whatgeometry,
                  out_of_bounds=False,
                  check_gradients=False):

    R01 = Rt01[:3, :]
    t01 = Rt01[3, :]

    # p now has shape (Np,3). The leading dims have been flattened
    p = p.reshape(p.size // 3, 3)
    Np = len(p)

    # p has shape (Np,3)
    # v has shape (Np,2)
    v0local_noisy, v1local_noisy,v0_noisy,v1_noisy,q0_ref,q1_ref,q0_noisy,q1_noisy = \
        [v[...,0,:] for v in \
         mrcal.synthetic_data.
         _noisy_observation_vectors_for_triangulation(p, Rt01,
                                                      model0.intrinsics(),
                                                      model1.intrinsics(),
                                                      1,
                                                      sigma = 0.1)]

    scenarios = \
        ( (mrcal.triangulate_geometric,      callback_l2_geometric,    v0_noisy,      v1_noisy,      t01),
          (mrcal.triangulate_leecivera_l1,   callback_l1_angle,        v0_noisy,      v1_noisy,      t01),
          (mrcal.triangulate_leecivera_linf, callback_linf_angle,      v0_noisy,      v1_noisy,      t01),
          (mrcal.triangulate_leecivera_mid2, None,                     v0_noisy,      v1_noisy,      t01),
          (mrcal.triangulate_leecivera_wmid2,None,                     v0_noisy,      v1_noisy,      t01),
          (mrcal.triangulate_lindstrom,      callback_l2_reprojection, v0local_noisy, v1local_noisy, Rt01),
         )

    for scenario in scenarios:

        f, callback = scenario[:2]
        args = scenario[2:]

        result = f(*args, get_gradients=True)
        p_reported = result[0]

        what = f"{whatgeometry} {f.__name__}"

        if out_of_bounds:
            p_optimized = np.zeros(p_reported.shape)
        else:
            # Check all the gradients
            if check_gradients:
                grads = result[1:]
                for ip in range(Np):
                    args_cut = (args[0][ip], args[1][ip], args[2])
                    for ivar in range(len(args)):
                        grad_empirical  = \
                            grad( lambda x: f( *args_cut[:ivar],
                                               x,
                                               *args_cut[ivar+1:]),
                                  args_cut[ivar],
                                  step = 1e-6)
                        testutils.confirm_equal(
                            grads[ivar][ip],
                            grad_empirical,
                            relative=True,
                            worstcase=True,
                            msg=f"{what}: grad(ip={ip}, ivar = {ivar})",
                            eps=2e-2)

            if callback is not None:

                # I run an optimization to directly optimize the quantity each triangulation
                # routine is supposed to be optimizing, and then I compare
                p_optimized = \
                    nps.cat(*[ scipy.optimize.minimize(callback,
                                                       p_reported[ip], # seed from the "right" value
                                                       args   = (args[0][ip], args[1][ip], args[2]),
                                                       method = 'Nelder-Mead',
                                                       # options = dict(disp  = True)
                                                       )['x'] \
                               for ip in range(Np) ])

                # print( f"{what} p reported,optimized:\n{nps.cat(p_reported, p_optimized)}" )
                # print( f"{what} p_err: {p_reported - p_optimized}" )
                # print( f"{what} optimum reported/optimized:\n{callback(p_reported, *args)/callback(p_optimized, *args)}" )

                testutils.confirm_equal(p_reported,
                                        p_optimized,
                                        relative=True,
                                        worstcase=True,
                                        msg=what,
                                        eps=1e-3)
            else:
                # No callback defined. Compare projected q
                q0 = mrcal.project(p_reported, *model0.intrinsics())
                q1 = mrcal.project(
                    mrcal.transform_point_Rt(mrcal.invert_Rt(Rt01),
                                             p_reported), *model1.intrinsics())

                testutils.confirm_equal(q0,
                                        q0_ref,
                                        relative=False,
                                        worstcase=True,
                                        msg=f'{what} q0',
                                        eps=25.)
                testutils.confirm_equal(q1,
                                        q1_ref,
                                        relative=False,
                                        worstcase=True,
                                        msg=f'{what} q1',
                                        eps=25.)
示例#5
0
                            el_fov_deg,
                            msg=f'complex stereo: el_fov ({lensmodel})',
                            eps = 0.5)

    # I examine points somewhere in space. I make sure the rectification maps
    # transform it properly. And I compute what its az,el and disparity would have
    # been, and I check the geometric functions
    pcam0 = np.array(((  1., 2., 12.),
                       (-4., 3., 12.)))

    qcam0 = mrcal.project( pcam0, *model0.intrinsics() )

    pcam1 = mrcal.transform_point_rt(mrcal.invert_rt(rt01), pcam0)
    qcam1 = mrcal.project( pcam1, *model1.intrinsics() )

    prect0 = mrcal.transform_point_Rt( mrcal.invert_Rt(Rt_cam0_rect), pcam0)
    prect1 = prect0 - Rt01_rectified[3,:]
    qrect0 = mrcal.project(prect0, *models_rectified[0].intrinsics())
    qrect1 = mrcal.project(prect1, *models_rectified[1].intrinsics())

    Naz,Nel = models_rectified[0].imagersize()

    row = np.arange(Naz, dtype=float)
    col = np.arange(Nel, dtype=float)

    rectification_maps = mrcal.rectification_maps((model0,model1),
                                                  models_rectified)

    interp_rectification_map0x = \
        scipy.interpolate.RectBivariateSpline(row, col,
                                              nps.transpose(rectification_maps[0][...,0]))
示例#6
0
    testutils.confirm_equal(
        nps.mag(Rt_extrinsics_err[3, :]),
        0.0,
        eps=0.05,
        msg=f"Recovered extrinsic translation for camera {icam}")

    testutils.confirm_equal(
        (np.trace(Rt_extrinsics_err[:3, :]) - 1) / 2.,
        1.0,
        eps=np.cos(1. * np.pi / 180.0),  # 1 deg
        msg=f"Recovered extrinsic rotation for camera {icam}")

Rt_frame_err = \
    mrcal.compose_Rt( mrcal.Rt_from_rt(optimization_inputs['frames_rt_toref']),
                      mrcal.invert_Rt(Rt_cam0_board_ref) )

testutils.confirm_equal(np.max(nps.mag(Rt_frame_err[..., 3, :])),
                        0.0,
                        eps=0.08,
                        msg="Recovered frame translation")
testutils.confirm_equal(
    np.min((nps.trace(Rt_frame_err[..., :3, :]) - 1) / 2.),
    1.0,
    eps=np.cos(1. * np.pi / 180.0),  # 1 deg
    msg="Recovered frame rotation")

# Checking the intrinsics. Each intrinsics vector encodes an implicit
# transformation. I compute and apply this transformation when making my
# intrinsics comparisons. I make sure that within some distance of the pixel
# center, the projections match up to within some number of pixels
示例#7
0
# I simulate pixel noise, and see what that does to the triangulation. Play with
# the geometric details to get a sense of how these behave

# square camera layout
t01  = np.array(( 1.,   0.1,  -0.2))
R01  = mrcal.R_from_r(np.array((0.001, -0.002, -0.003)))
Rt01 = nps.glue(R01, t01, axis=-2)

p  = np.array(( 5000., 300.,  2000.))
q0 = mrcal.project(p, *model0.intrinsics())

Nsamples = 2000
sigma    = 0.1

v0local_noisy, v1local_noisy,v0_noisy,v1_noisy,_,_,_,_ = \
    noisy_observation_vectors(p, mrcal.invert_Rt(Rt01),
                              Nsamples, sigma = sigma)

p_sampled_geometric       = mrcal.triangulate_geometric(      v0_noisy,      v1_noisy,      t01 )
p_sampled_lindstrom       = mrcal.triangulate_lindstrom(      v0local_noisy, v1local_noisy, Rt01 )
p_sampled_leecivera_l1    = mrcal.triangulate_leecivera_l1(   v0_noisy,      v1_noisy,      t01 )
p_sampled_leecivera_linf  = mrcal.triangulate_leecivera_linf( v0_noisy,      v1_noisy,      t01 )
p_sampled_leecivera_mid2  = mrcal.triangulate_leecivera_mid2( v0_noisy,      v1_noisy,      t01 )
p_sampled_leecivera_wmid2 = mrcal.triangulate_leecivera_wmid2(v0_noisy,      v1_noisy,      t01 )

q0_sampled_geometric       = mrcal.project(p_sampled_geometric,      *model0.intrinsics())
q0_sampled_lindstrom       = mrcal.project(p_sampled_lindstrom,      *model0.intrinsics())
q0_sampled_leecivera_l1    = mrcal.project(p_sampled_leecivera_l1,   *model0.intrinsics())
q0_sampled_leecivera_linf  = mrcal.project(p_sampled_leecivera_linf, *model0.intrinsics())
q0_sampled_leecivera_mid2  = mrcal.project(p_sampled_leecivera_mid2, *model0.intrinsics())
q0_sampled_leecivera_wmid2 = mrcal.project(p_sampled_leecivera_wmid2, *model0.intrinsics())
示例#8
0
    0.0005275929652,
    0.01968883397,
    0.01482863541,
    -0.0562239888,
    0.0500223357,
])

rt_0r = np.array([
    4e-1,
    -1e-2,
    1e-3,
    -2.,
    3,
    -5.,
])
Rt_r0 = mrcal.invert_Rt(mrcal.Rt_from_rt(rt_0r))
m.extrinsics_Rt_toref(Rt_r0)
testutils.confirm_equal(m.extrinsics_rt_fromref(), rt_0r)

# Let's make sure I can read and write empty and non-empty valid-intrinsics
# regions
m = mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel")
testutils.confirm_equal(m.valid_intrinsics_region(), None,
                        "read 'valid_intrinsics_region is None' properly")

r_open = np.array(((0, 0), (0, 10), (10, 10), (10, 0)))
r_closed = np.array(((0, 0), (0, 10), (10, 10), (10, 0), (0, 0)))
r_empty = np.zeros((0, 2))

m.valid_intrinsics_region(r_open)
testutils.confirm_equal(
示例#9
0
        mrcal.compose_Rt( models_solved[icam].extrinsics_Rt_fromref(),
                          models_ref   [icam].extrinsics_Rt_toref() )

    testutils.confirm_equal( nps.mag(Rt_extrinsics_err[3,:]),
                             0.0,
                             eps = 0.05,
                             msg = f"Recovered extrinsic translation for camera {icam}")

    testutils.confirm_equal( (np.trace(Rt_extrinsics_err[:3,:]) - 1) / 2.,
                             1.0,
                             eps = np.cos(1. * np.pi/180.0), # 1 deg
                             msg = f"Recovered extrinsic rotation for camera {icam}")

Rt_frame_err = \
    mrcal.compose_Rt( mrcal.Rt_from_rt(optimization_inputs['frames_rt_toref']),
                      mrcal.invert_Rt(Rt_ref_board_ref) )

testutils.confirm_equal( np.max(nps.mag(Rt_frame_err[..., 3,:])),
                         0.0,
                         eps = 0.08,
                         msg = "Recovered frame translation")
testutils.confirm_equal( np.min( (nps.trace(Rt_frame_err[..., :3,:]) - 1)/2. ),
                         1.0,
                         eps = np.cos(1. * np.pi/180.0), # 1 deg
                         msg = "Recovered frame rotation")


# Checking the intrinsics. Each intrinsics vector encodes an implicit
# transformation. I compute and apply this transformation when making my
# intrinsics comparisons. I make sure that within some distance of the pixel
# center, the projections match up to within some number of pixels
示例#10
0
def image_transformation_map(model_from,
                             model_to,
                             intrinsics_only=False,
                             distance=None,
                             plane_n=None,
                             plane_d=None,
                             mask_valid_intrinsics_region_from=False):
    r'''Compute a reprojection map between two models

SYNOPSIS

    model_orig = mrcal.cameramodel("xxx.cameramodel")
    image_orig = cv2.imread("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()

    '''

    if (plane_n is      None and plane_d is not None) or \
       (plane_n is not  None and plane_d is     None):
        raise Exception(
            "plane_n and plane_d should both be None or neither should be None"
        )
    if plane_n is not None and \
       intrinsics_only:
        raise Exception(
            "We're looking at remapping a plane (plane_d, plane_n are not None), so intrinsics_only should be False"
        )

    if distance is not None and \
       (plane_n is not None or intrinsics_only):
        raise Exception(
            "'distance' makes sense only without plane_n/plane_d and without intrinsics_only"
        )

    if intrinsics_only:
        Rt_to_from = None
    else:
        Rt_to_from = mrcal.compose_Rt(model_to.extrinsics_Rt_fromref(),
                                      model_from.extrinsics_Rt_toref())

    lensmodel_from, intrinsics_data_from = model_from.intrinsics()
    lensmodel_to, intrinsics_data_to = model_to.intrinsics()

    if re.match("LENSMODEL_OPENCV",lensmodel_from) and \
       lensmodel_to == "LENSMODEL_PINHOLE"         and \
       plane_n is None                             and \
       not mask_valid_intrinsics_region_from       and \
       distance is None:

        # This is a common special case. This branch works identically to the
        # other path (the other side of this "if" can always be used instead),
        # but the opencv-specific code is optimized and at one point ran faster
        # than the code on the other side.
        #
        # The mask_valid_intrinsics_region_from isn't implemented in this path.
        # It COULD be, then this faster path could be used
        import cv2

        fxy_from = intrinsics_data_from[0:2]
        cxy_from = intrinsics_data_from[2:4]
        cameraMatrix_from = np.array(
            ((fxy_from[0], 0, cxy_from[0]), (0, fxy_from[1], cxy_from[1]),
             (0, 0, 1)))

        fxy_to = intrinsics_data_to[0:2]
        cxy_to = intrinsics_data_to[2:4]
        cameraMatrix_to = np.array(
            ((fxy_to[0], 0, cxy_to[0]), (0, fxy_to[1], cxy_to[1]), (0, 0, 1)))

        output_shape = model_to.imagersize()
        distortion_coeffs = intrinsics_data_from[4:]

        if Rt_to_from is not None:
            R_to_from = Rt_to_from[:3, :]
            if np.trace(R_to_from) > 3. - 1e-12:
                R_to_from = None  # identity, so I pass None
        else:
            R_to_from = None

        return nps.glue( *[ nps.dummy(arr,-1) for arr in \
                            cv2.initUndistortRectifyMap(cameraMatrix_from, distortion_coeffs,
                                                        R_to_from,
                                                        cameraMatrix_to, tuple(output_shape),
                                                        cv2.CV_32FC1)],
                         axis = -1)

    W_from, H_from = model_from.imagersize()
    W_to, H_to = model_to.imagersize()

    # shape: (Nheight,Nwidth,2). Contains (x,y) rows
    grid = np.ascontiguousarray(nps.mv(
        nps.cat(*np.meshgrid(np.arange(W_to), np.arange(H_to))), 0, -1),
                                dtype=float)
    v = mrcal.unproject(grid, lensmodel_to, intrinsics_data_to)

    if plane_n is not None:

        R_to_from = Rt_to_from[:3, :]
        t_to_from = Rt_to_from[3, :]

        # The homography definition. Derived in many places. For instance in
        # "Motion and structure from motion in a piecewise planar environment"
        # by Olivier Faugeras, F. Lustman.
        A_to_from = plane_d * R_to_from + nps.outer(t_to_from, plane_n)
        A_from_to = np.linalg.inv(A_to_from)
        v = nps.matmult(v, nps.transpose(A_from_to))

    else:
        if Rt_to_from is not None:
            if distance is not None:
                v = mrcal.transform_point_Rt(
                    mrcal.invert_Rt(Rt_to_from),
                    v / nps.dummy(nps.mag(v), -1) * distance)
            else:
                R_to_from = Rt_to_from[:3, :]
                v = nps.matmult(v, R_to_from)

    mapxy = mrcal.project(v, lensmodel_from, intrinsics_data_from)

    if mask_valid_intrinsics_region_from:

        # Using matplotlib to compute the out-of-bounds points. It doesn't
        # support broadcasting, so I do that manually with a clump/reshape
        from matplotlib.path import Path
        region = Path(model_from.valid_intrinsics_region())
        is_inside = region.contains_points(nps.clump(mapxy, n=2)).reshape(
            mapxy.shape[:2])
        mapxy[~is_inside, :] = -1

    return mapxy.astype(np.float32)
示例#11
0
        except:
            pass

    # Generate the rectification maps
    if kind != "narrow":
        azel_kwargs = dict(az_fov_deg=145., el_fov_deg=135., el0_deg=5)
    else:
        azel_kwargs = dict(az_fov_deg=80., el_fov_deg=80., el0_deg=0)
    rectification_maps, cookie = \
        mrcal.stereo_rectify_prepare(models, **azel_kwargs)

    # Display the geometry of the two cameras in the stereo pair, and of the
    # rectified system
    Rt_cam0_stereo = cookie['Rt_cam0_stereo']
    Rt_cam0_ref = models[0].extrinsics_Rt_fromref()
    Rt_stereo_ref = mrcal.compose_Rt(mrcal.invert_Rt(Rt_cam0_stereo),
                                     Rt_cam0_ref)
    rt_stereo_ref = mrcal.rt_from_Rt(Rt_stereo_ref)

    terminal = dict(
        pdf='pdf size 8in,6in       noenhanced solid color      font ",12"',
        svg='svg size 800,600       noenhanced solid dynamic    font ",14"',
        png='pngcairo size 1024,768 transparent noenhanced crop font ",12"',
        gp='gp')
    for extension in terminal.keys():
        mrcal.show_geometry(
            models + [rt_stereo_ref], ("camera0", "camera1", "stereo"),
            show_calobjects=False,
            _set=('xyplane at -0.5', 'view 60,30,1.7'),
            terminal=terminal[extension],
            hardcopy=f'/tmp/stereo-geometry-{kind}.{extension}')
示例#12
0
文件: stereo.py 项目: vonj/mrcal
def stereo_rectify_prepare(models,
                           az_fov_deg,
                           el_fov_deg,
                           az0_deg           = None,
                           el0_deg           = 0,
                           pixels_per_deg_az = None,
                           pixels_per_deg_el = None):

    r'''Precompute everything needed for stereo rectification and matching

SYNOPSIS

    import sys
    import mrcal
    import cv2
    import numpy as np

    # Read commandline arguments: model0 model1 image0 image1
    models = [ mrcal.cameramodel(sys.argv[1]),
               mrcal.cameramodel(sys.argv[2]), ]

    images = [ cv2.imread(sys.argv[i]) \
               for i in (3,4) ]

    # Prepare the stereo system
    rectification_maps,cookie = \
        mrcal.stereo_rectify_prepare(models,
                                     az_fov_deg = 120,
                                     el_fov_deg = 100)

    # Visualize the geometry of the two cameras and of the rotated stereo
    # coordinate system
    Rt_cam0_ref    = models[0].extrinsics_Rt_fromref()
    Rt_cam0_stereo = cookie['Rt_cam0_stereo']
    Rt_stereo_ref  = mrcal.compose_Rt( mrcal.invert_Rt(Rt_cam0_stereo),
                                       Rt_cam0_ref )
    rt_stereo_ref  = mrcal.rt_from_Rt(Rt_stereo_ref)

    mrcal.show_geometry( models + [ rt_stereo_ref ],
                         ( "camera0", "camera1", "stereo" ),
                         show_calobjects = False,
                         wait            = True )

    # Rectify the images
    images_rectified = \
      [ mrcal.transform_image(images[i], rectification_maps[i]) \
        for i in range(2) ]

    cv2.imwrite('/tmp/rectified0.jpg', images_rectified[0])
    cv2.imwrite('/tmp/rectified1.jpg', images_rectified[1])

    # Find stereo correspondences using OpenCV
    block_size = 3
    max_disp   = 160 # in pixels
    stereo = \
        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 = stereo.compute(*images_rectified) # in pixels*16

    cv2.imwrite('/tmp/disparity.png',
                mrcal.apply_color_map(disparity16,
                                      0, max_disp*16.))

    # Convert the disparities to range to camera0
    r = mrcal.stereo_range( disparity16.astype(np.float32) / 16.,
                            **cookie )

    cv2.imwrite('/tmp/range.png', mrcal.apply_color_map(r, 5, 1000))

This function does the initial computation required to perform stereo matching,
and to get ranges from a stereo pair. It computes

- the pose of the rectified stereo coordinate system

- the azimuth/elevation grid used in the rectified images

- the rectification maps used to transform images into the rectified space

Using the results of one call to this function we can compute the stereo
disparities of many pairs of synchronized images.

This function is generic: the two cameras may have 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 set up stereo matching
using this function. The input images are tranformed into a "rectified" space.
Geometrically, the rectified coordinate system sits at the origin of camera0,
with a rotation. The axes of the rectified coordinate system:

- x: from the origin of camera0 to the origin of camera1 (the baseline direction)

- y: completes the system from x,z

- z: the "forward" direction of the two cameras, with the component parallel to
     the baseline subtracted off

In a nominal geometry (the two cameras are square with each other, camera1
strictly to the right of camera0), the rectified coordinate system exactly
matches the coordinate system of camera0. The above formulation supports any
geometry, however, including vertical and/or forward/backward shifts. Vertical
stereo is supported.

Rectified images represent 3D planes intersecting the origins of the two
cameras. The tilt of each plane is the "elevation". While the left/right
direction inside each plane is the "azimuth". We generate rectified images where
each pixel coordinate represents (x = azimuth, y = elevation). Thus each row
scans the azimuths in a particular elevation, and thus each row in the two
rectified images represents the same plane in 3D, and matching features in each
row can produce a stereo disparity and a range.

In the rectified system, elevation is a rotation along the x axis, while azimuth
is a rotation normal to the resulting tilted plane.

We produce rectified images whose pixel coordinates are linear with azimuths and
elevations. This means that the azimuth angular resolution is constant
everywhere, even at the edges of a wide-angle image.

We return a set of transformation maps and a cookie. The maps can be used to
generate rectified images. These rectified images can be processed by any
stereo-matching routine to generate a disparity image. To interpret the
disparity image, call stereo_unproject() or stereo_range() with the cookie
returned here.

The cookie is a Python dict that describes the rectified space. It is guaranteed
to have the following keys:

- Rt_cam0_stereo: an Rt transformation to map a representation of points in the
  rectified coordinate system to a representation in the camera0 coordinate system

- baseline: the distance between the two cameras

- az_row: an array of shape (Naz,) describing the azimuths in each row of the
  disparity image

- el_col: an array of shape (Nel,1) describing the elevations in each column of
  the disparity image

ARGUMENTS

- models: an iterable of two mrcal.cameramodel objects representing the cameras
  in the stereo system. 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 view, in pixels

- el_fov_deg: required value for the elevation (across-the-baseline)
  field-of-view of the desired rectified view, in pixels

- 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 azimuth = 0 is no longer at the center of the input
  images. If omitted, we compute the center azimuth that aligns with the center
  of the cameras' view

- 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 omitted (or None), we use the resolution of the input image at
  (azimuth, elevation) = 0. If a resolution of <0 is requested, we use this as a
  scale factor on the resolution of the input image. For instance, to downsample
  by a factor of 2, pass pixels_per_deg_az = -0.5

- pixels_per_deg_el: same as pixels_per_deg_az but in the elevation direction

RETURNED VALUES

We return a tuple

- transformation maps: a tuple of length-2 containing transformation maps for
  each camera. Each map can be used to mrcal.transform_image() images to the
  rectified space

- cookie: a dict describing the rectified space. Intended as input to
  stereo_unproject() and stereo_range(). See the description above for more
  detail

    '''

    if len(models) != 2:
        raise Exception("I need exactly 2 camera models")

    def normalize(v):
        v /= nps.mag(v)
        return v

    def remove_projection(a, proj_base):
        r'''Returns the normalized component of a orthogonal to proj_base

        proj_base assumed normalized'''
        v = a - nps.inner(a,proj_base)*proj_base
        return normalize(v)

    ######## Compute the geometry of the rectified stereo system. This is a
    ######## rotation, centered at camera0. More or less we have axes:
    ########
    ######## x: from camera0 to camera1
    ######## y: completes the system from x,z
    ######## z: component of the cameras' viewing direction
    ########    normal to the baseline
    Rt_cam0_ref = models[0].extrinsics_Rt_fromref()
    Rt01 = mrcal.compose_Rt( Rt_cam0_ref,
                             models[1].extrinsics_Rt_toref())
    Rt10 = mrcal.invert_Rt(Rt01)

    # Rotation relating camera0 coords to the rectified camera coords. I fill in
    # each row separately
    R_stereo_cam0 = np.zeros((3,3), dtype=float)
    right         = R_stereo_cam0[0,:]
    down          = R_stereo_cam0[1,:]
    forward       = R_stereo_cam0[2,:]

    # "right" of the rectified coord system: towards the origin of camera1 from
    # camera0, in camera0 coords
    right[:] = Rt01[3,:]
    baseline = nps.mag(right)
    right   /= baseline

    # "forward" for each of the two cameras, in the cam0 coord system
    forward0 = np.array((0,0,1.))
    forward1 = Rt01[:3,2]

    # "forward" of the rectified coord system, in camera0 coords. The mean of
    # the two non-right "forward" directions
    forward[:] = normalize( ( remove_projection(forward0,right) +
                              remove_projection(forward1,right) ) / 2. )

    # "down" of the rectified coord system, in camera0 coords. Completes the
    # right,down,forward coordinate system
    down[:] = np.cross(forward,right)

    R_cam0_stereo = nps.transpose(R_stereo_cam0)



    ######## Done with the geometry! Now to get the az/el grid. I need to figure
    ######## out the resolution and the extents


    if az0_deg is not None:
        az0 = az0_deg * np.pi/180.

    else:
        # In the rectified system az=0 sits perpendicular to the baseline.
        # Normally the cameras are looking out perpendicular to the baseline
        # also, so I center my azimuth samples around 0 to match the cameras'
        # field of view. But what if the geometry isn't square, and one camera
        # is behind the other? Like this:
        #
        #    camera
        #     view
        #       ^
        #       |
        #     \ | /
        #      \_/
        #        .    /
        #         .  /az=0
        #          ./
        #           .
        #  baseline  .
        #             .
        #            \   /
        #             \_/
        #
        # Here the center-of-view axis of each camera is not at all
        # perpendicular to the baseline. Thus I compute the mean "forward"
        # direction of the cameras in the rectified system, and set that as the
        # center azimuth az0.
        v0 = nps.matmult( forward0, R_cam0_stereo ).ravel()
        v1 = nps.matmult( forward1, R_cam0_stereo ).ravel()
        v0[1] = 0.0
        v1[1] = 0.0
        normalize(v0)
        normalize(v1)
        v = v0 + v1
        az0 = np.arctan2(v[0],v[2])


    el0 = el0_deg * np.pi/180.

    ####### Rectified image resolution
    if pixels_per_deg_az is None or pixels_per_deg_az < 0 or \
       pixels_per_deg_el is None or pixels_per_deg_el < 0:
        # I need to compute the resolution of the rectified images. I try to
        # match the resolution of the cameras. I just look at camera0. If you
        # have different cameras, pass in pixels_per_deg yourself :)
        #
        # I look at the center of the stereo field of view. There I have q =
        # project(v) where v is a unit projection vector. I compute dq/dth where
        # th is an angular perturbation applied to v.
        def rotation_any_v_to_z(v):
            r'''Return any rotation matrix that maps the given unit vector v to [0,0,1]'''
            z = v
            if np.abs(v[0]) < .9:
                x = np.array((1,0,0))
            else:
                x = np.array((0,1,0))
            x -= nps.inner(x,v)*v
            x /= nps.mag(x)
            y = np.cross(z,x)

            return nps.cat(x,y,z)


        v, dv_dazel = stereo_unproject(az0, el0, get_gradients = True)
        v0          = mrcal.rotate_point_R(R_cam0_stereo, v)
        dv0_dazel   = nps.matmult(R_cam0_stereo, dv_dazel)

        _,dq_dv0,_ = mrcal.project(v0, *models[0].intrinsics(), get_gradients = True)

        # I rotate my v to a coordinate system where u = rotate(v) is [0,0,1].
        # Then u = [a,b,0] are all orthogonal to v. So du/dth = [cos, sin, 0].
        # I then have dq/dth = dq/dv dv/du [cos, sin, 0]t
        # ---> dq/dth = dq/dv dv/du[:,:2] [cos, sin]t = M [cos,sin]t
        #
        # norm2(dq/dth) = [cos,sin] MtM [cos,sin]t is then an ellipse with the
        # eigenvalues of MtM giving me the best and worst sensitivities. I can
        # use mrcal.worst_direction_stdev() to find the densest direction. But I
        # actually know the directions I care about, so I evaluate them
        # independently for the az and el directions

        # Ruv = rotation_any_v_to_z(v0)
        # M = nps.matmult(dq_dv0, nps.transpose(Ruv[:2,:]))
        # # I pick the densest direction: highest |dq/dth|
        # pixels_per_rad = mrcal.worst_direction_stdev( nps.matmult( nps.transpose(M),M) )

        if pixels_per_deg_az is None or pixels_per_deg_az < 0:
            dq_daz = nps.inner( dq_dv0, dv0_dazel[:,0] )
            pixels_per_rad_az_have = nps.mag(dq_daz)

            if pixels_per_deg_az is not None:
                # negative pixels_per_deg_az requested means I use the requested
                # value as a scaling
                pixels_per_deg_az = -pixels_per_deg_az * pixels_per_rad_az_have*np.pi/180.
            else:
                pixels_per_deg_az = pixels_per_rad_az_have*np.pi/180.

        if pixels_per_deg_el is None or pixels_per_deg_el < 0:
            dq_del = nps.inner( dq_dv0, dv0_dazel[:,1] )
            pixels_per_rad_el_have = nps.mag(dq_del)

            if pixels_per_deg_el is not None:
                # negative pixels_per_deg_el requested means I use the requested
                # value as a scaling
                pixels_per_deg_el = -pixels_per_deg_el * pixels_per_rad_el_have*np.pi/180.
            else:
                pixels_per_deg_el = pixels_per_rad_el_have*np.pi/180.



    Naz = round(az_fov_deg*pixels_per_deg_az)
    Nel = round(el_fov_deg*pixels_per_deg_el)

    # Adjust the fov to keep the requested resolution and pixel counts
    az_fov_radius_deg = Naz / (2.*pixels_per_deg_az)
    el_fov_radius_deg = Nel / (2.*pixels_per_deg_el)

    # shape (Naz,)
    az = np.linspace(az0 - az_fov_radius_deg*np.pi/180.,
                     az0 + az_fov_radius_deg*np.pi/180.,
                     Naz)
    # shape (Nel,1)
    el = nps.dummy( np.linspace(el0 - el_fov_radius_deg*np.pi/180.,
                                el0 + el_fov_radius_deg*np.pi/180.,
                                Nel),
                    -1 )

    # v has shape (Nel,Naz,3)
    v = stereo_unproject(az, el)

    v0 = nps.matmult( nps.dummy(v,  -2), R_stereo_cam0 )[...,0,:]
    v1 = nps.matmult( nps.dummy(v0, -2), Rt01[:3,:]    )[...,0,:]

    cookie = \
        dict( Rt_cam0_stereo    = nps.glue(R_cam0_stereo, np.zeros((3,)), axis=-2),
              baseline          = baseline,
              az_row            = az,
              el_col            = el,

              # The caller should NOT assume these are available in the cookie:
              # some other rectification scheme may not produce linear az/el
              # maps
              pixels_per_deg_az = pixels_per_deg_az,
              pixels_per_deg_el = pixels_per_deg_el,
            )

    return                                                                \
        (mrcal.project( v0, *models[0].intrinsics()).astype(np.float32),  \
         mrcal.project( v1, *models[1].intrinsics()).astype(np.float32)), \
        cookie
示例#13
0
文件: test-stereo.py 项目: vonj/mrcal
                        msg='funny stereo geometry')

testutils.confirm_equal(cookie['baseline'],
                        nps.mag(rt01[3:]),
                        msg='funny stereo: baseline')

# I examine points somewhere in space. I make sure the rectification maps
# transform it properly. And I compute what its az,el and disparity would have
# been, and I check the geometric functions
pcam0 = np.array(((1., 2., 10.), (-4., 3., 10.)))
qcam0 = mrcal.project(pcam0, *model0.intrinsics())

pcam1 = mrcal.transform_point_rt(mrcal.invert_rt(rt01), pcam0)
qcam1 = mrcal.project(pcam1, *model1.intrinsics())

pstereo0 = mrcal.transform_point_Rt(mrcal.invert_Rt(Rt_cam0_stereo), pcam0)
el0 = np.arctan2(pstereo0[:, 1], pstereo0[:, 2])
az0 = np.arctan2(pstereo0[:, 0], pstereo0[:, 2] / np.cos(el0))

pstereo1 = pstereo0 - np.array((cookie['baseline'], 0, 0))
el1 = np.arctan2(pstereo1[:, 1], pstereo1[:, 2])
az1 = np.arctan2(pstereo1[:, 0], pstereo1[:, 2] / np.cos(el1))

disparity = az0 - az1


interp_rectification_map0x = \
    scipy.interpolate.RectBivariateSpline(cookie['az_row'].ravel(),
                                          cookie['el_col'].ravel(),
                                          nps.transpose(rectification_maps[0][...,0]))
interp_rectification_map0y = \
示例#14
0
confirm_equal(rt, rt0_ref, msg='rt_from_Rt result')

rt, J_R = mrcal.rt_from_Rt(Rt0_ref, get_gradients=True, out=(out6, out333))
J_R_ref = grad(r_from_R, Rt0_ref[:3, :])
confirm_equal(rt, rt0_ref, msg='rt_from_Rt result')
confirm_equal(J_R, J_R_ref, msg='rt_from_Rt grad result')

Rt = mrcal.Rt_from_rt(rt0_ref, out=out43)
confirm_equal(Rt, Rt0_ref, msg='Rt_from_rt result')

Rt, J_r = mrcal.Rt_from_rt(rt0_ref, get_gradients=True, out=(out43, out333))
J_r_ref = grad(R_from_r, rt0_ref[:3])
confirm_equal(Rt, Rt0_ref, msg='Rt_from_rt result')
confirm_equal(J_r, J_r_ref, msg='Rt_from_rt grad result')

Rt = mrcal.invert_Rt(Rt0_ref, out=out43)
confirm_equal(Rt, invert_Rt(Rt0_ref), msg='invert_Rt result')

rt = mrcal.invert_rt(rt0_ref, out=out6)
confirm_equal(rt, invert_rt(rt0_ref), msg='invert_rt result')

rt, drt_drt = mrcal.invert_rt(rt0_ref, get_gradients=True, out=(out6, out66))
drt_drt_ref = grad(invert_rt, rt0_ref)
confirm_equal(rt, invert_rt(rt0_ref), msg='invert_rt with grad result')
confirm_equal(drt_drt, drt_drt_ref, msg='invert_rt drt/drt result')

Rt2 = mrcal.compose_Rt(Rt0_ref, Rt1_ref, out=out43)
confirm_equal(Rt2, compose_Rt(Rt0_ref, Rt1_ref), msg='compose_Rt result')

rt2 = mrcal.compose_rt(rt0_ref, rt1_ref, out=out6)
confirm_equal(rt2, compose_rt(rt0_ref, rt1_ref), msg='compose_rt result')
                             allow_nonidentity_cam0_transform = False)
else:
    with open(cache_file, "rb") as f:
        (optimization_inputs_baseline, models_true, models_baseline,
         indices_frame_camintrinsics_camextrinsics, lensmodel, Nintrinsics,
         imagersizes, intrinsics_true, extrinsics_true_mounted, frames_true,
         observations_true, intrinsics_sampled, extrinsics_sampled_mounted,
         frames_sampled, calobject_warp_sampled) = pickle.load(f)

baseline_rt_ref_frame = optimization_inputs_baseline['frames_rt_toref']

icam0, icam1 = args.cameras

Rt01_true = mrcal.compose_Rt(
    mrcal.Rt_from_rt(extrinsics_rt_fromref_true[icam0]),
    mrcal.invert_Rt(mrcal.Rt_from_rt(extrinsics_rt_fromref_true[icam1])))
Rt10_true = mrcal.invert_Rt(Rt01_true)

# shape (Npoints,Ncameras,3)
p_triangulated_true_local = nps.xchg(
    nps.cat(p_triangulated_true0,
            mrcal.transform_point_Rt(Rt10_true, p_triangulated_true0)), 0, 1)

# Pixel coords at the perfect intersection
# shape (Npoints,Ncameras,2)
q_true = nps.xchg( np.array([ mrcal.project(p_triangulated_true_local[:,i,:],
                                            lensmodel,
                                            intrinsics_true[args.cameras[i]]) \
                            for i in range(2)]),
                 0,1)
示例#16
0
confirm_equal(rt, rt0_ref, msg='rt_from_Rt result')

rt, J_R = mrcal.rt_from_Rt(Rt0_ref, get_gradients=True, out=(out6, out333))
J_R_ref = grad(r_from_R, Rt0_ref[:3, :])
confirm_equal(rt, rt0_ref, msg='rt_from_Rt result')
confirm_equal(J_R, J_R_ref, msg='rt_from_Rt grad result')

Rt = mrcal.Rt_from_rt(rt0_ref, out=out43)
confirm_equal(Rt, Rt0_ref, msg='Rt_from_rt result')

Rt, J_r = mrcal.Rt_from_rt(rt0_ref, get_gradients=True, out=(out43, out333))
J_r_ref = grad(R_from_r, rt0_ref[:3])
confirm_equal(Rt, Rt0_ref, msg='Rt_from_rt result')
confirm_equal(J_r, J_r_ref, msg='Rt_from_rt grad result')

Rt = mrcal.invert_Rt(Rt0_ref, out=out43)
confirm_equal(Rt, invert_Rt(Rt0_ref), msg='invert_Rt result')

# in-place
Rt0_ref_copy = np.array(Rt0_ref)
Rt = mrcal.invert_Rt(Rt0_ref_copy, out=Rt0_ref_copy)
confirm_equal(Rt, invert_Rt(Rt0_ref), msg='invert_Rt result written in-place')

R = mrcal.invert_R(R0_ref, out=out33)
confirm_equal(R, invert_R(R0_ref), msg='invert_R result')

# in-place
R0_ref_copy = np.array(R0_ref)
R = mrcal.invert_R(R0_ref_copy, out=R0_ref_copy)
confirm_equal(R, invert_R(R0_ref), msg='invert_R result written in-place')
示例#17
0
    mrcal.align_procrustes_points_Rt01(Tp + noise,
                                       p)
R_fit = Rt_fit[:3, :]
t_fit = Rt_fit[3, :]
testutils.confirm_equal(R_fit, R, eps=1e-2, msg='Procrustes fit R')
testutils.confirm_equal(t_fit, t, eps=1e-2, msg='Procrustes fit t')

R_fit_vectors = \
    mrcal.align_procrustes_vectors_R01(nps.matmult( p, nps.transpose(R) ) + noise,
                                       p)
testutils.confirm_equal(R_fit_vectors,
                        R,
                        eps=1e-2,
                        msg='Procrustes fit R (vectors)')

testutils.confirm_equal(mrcal.invert_Rt(
    mrcal.Rt_from_rt(mrcal.invert_rt(mrcal.rt_from_Rt(Rt)))),
                        Rt,
                        msg='Rt/rt and invert')

testutils.confirm_equal(mrcal.compose_Rt(Rt, mrcal.invert_Rt(Rt)),
                        nps.glue(np.eye(3), np.zeros((3, )), axis=-2),
                        msg='compose_Rt')

testutils.confirm_equal(mrcal.compose_rt(mrcal.rt_from_Rt(Rt),
                                         mrcal.invert_rt(
                                             mrcal.rt_from_Rt(Rt))),
                        np.zeros((6, )),
                        msg='compose_rt')

testutils.confirm_equal(mrcal.identity_Rt(),
                        nps.glue(np.eye(3), np.zeros((3, )), axis=-2),