def test_on_static_muti_tag():
    """
    connect track and close with multi tag,
    reqs: 03, 04 ,05, 07
    """
    config = {
        'video source': 'data/12markers.avi',
        'aruco dictionary': 'DICT_6X6_250'
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    (port_handles, timestamps, framenumbers, tracking,
     quality) = tracker.get_frame()
    assert len(port_handles) == len(timestamps)
    assert len(port_handles) == len(framenumbers)
    assert len(port_handles) == len(tracking)
    assert len(port_handles) == len(quality)
    assert len(port_handles) == 12
    for tagid in range(1, 13):
        tag_name = str('DICT_6X6_250:' + str(tagid))
        assert tag_name in port_handles

    regression_array6 = np.array([[1., 0., 0., 262.5], [0., 1., 0., 241.5],
                                  [0., 0., 1., -151.32085], [0., 0., 0., 1.]])

    assert np.allclose(tracking[port_handles.index('DICT_6X6_250:6')],
                       regression_array6)

    tracker.stop_tracking()
    tracker.close()
def test_with_tool_desc_and_calib():
    """
    connect track and close with multitags, defined
    rigid bodies, and camera calibration
    reqs: 03, 04 ,05, 07
    """
    config = {
        'video source':
        'data/multipattern.avi',
        'calibration':
        'data/calibration.txt',
        'rigid bodies': [{
            'name': 'reference',
            'filename': 'data/reference.txt',
            'aruco dictionary': 'DICT_ARUCO_ORIGINAL',
            'tag width': 49.50
        }, {
            'name': 'pointer',
            'filename': 'data/pointer.txt',
            'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
        }]
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    assert tracker.has_capture()
    (port_handles, timestamps, framenumbers, tracking,
     quality) = tracker.get_frame()
    assert len(port_handles) == len(timestamps)
    assert len(port_handles) == len(framenumbers)
    assert len(port_handles) == len(tracking)
    assert len(port_handles) == len(quality)
    assert len(port_handles) == 4  #there is an extraneous marker (1000)
    assert 'reference' in port_handles
    assert 'pointer' in port_handles
    assert 'DICT_4X4_50:0' in port_handles

    reference_index = port_handles.index('reference')
    pointer_index = port_handles.index('pointer')

    assert np.isclose(quality[reference_index], 0.91666666)
    assert np.isclose(quality[pointer_index], 0.83333333)

    ref_regression = np.array(
        [[-0.84701057, 0.51884094, -0.11565978, -8.22903442e+01],
         [-0.48733129, -0.67100208, 0.55880625, 4.85032501e+01],
         [0.21232361, 0.52967943, 0.82119327, 2.43992401e+02],
         [0.00000000e+00, 0.00000000e+00, 0.00000000e+00, 1.00000000e+00]],
        dtype=np.float32)

    assert np.allclose(tracking[reference_index], ref_regression)

    tracker.stop_tracking()
    tracker.close()
def test_on_video_with_debug():
    """
    connect track and close with single tag, with debug flag on
    debug should open a separate window showing the image capture
    reqs: 03, 04 ,05
    """
    config = {'video source': 'data/output.avi', 'debug': True}

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    for frame in range(2):
        (port_handles, timestamps, framenumbers, tracking,
         quality) = tracker.get_frame()
        assert len(port_handles) == len(timestamps)
        assert len(port_handles) == len(framenumbers)
        assert len(port_handles) == len(tracking)
        assert len(port_handles) == len(quality)
        assert len(port_handles) == 1
        assert port_handles[0] == 'DICT_4X4_50:0'
        assert framenumbers[0] == frame
        assert quality[0] == 1.0

    tracker.stop_tracking()
    tracker.close()
def test_on_video_with_calib():
    """
    connect track and close with single tag,
    and calibrated camera
    reqs: 03, 04 ,05
    """
    config1 = {
        'video source': 'data/output.avi',
        'calibration': 'data/calibration.txt',
        'marker size': 50,
    }

    tracker = ArUcoTracker(config1)
    tracker.start_tracking()
    for frame in range(10):
        (port_handles, _timestamps, _framenumbers, tracking,
         _quality) = tracker.get_frame()
        if frame == 1:

            regression_array = np.array(
                [[0.99928828, -0.02261964, 0.03018762, 1.7609988e+01],
                 [-0.02280416, -0.99972323, 0.00578211, 2.5085676e+01],
                 [0.03004847, -0.00646639, -0.99952753, 2.1036779e+02],
                 [0., 0., 0., 1.]])

            assert np.allclose(tracking[port_handles.index('DICT_4X4_50:0')],
                               regression_array)

    tracker.stop_tracking()
    tracker.close()
def test_iteration_over_empty_dicts():
    """
    Tests that when no markers are detected in an early
    dictionary, we continue to iterate over the remainder
    issue #29
    """

    config = {
        'video source':
        'data/multipattern.avi',
        'rigid bodies': [
            {
                'name': 'bad_pointer',
                'filename': 'data/pointer.txt',
                'aruco dictionary': 'DICT_7X7_250'
            },
            {
                'name': 'reference',
                'filename': 'data/reference.txt',
                'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
            },
            {
                'name': 'good_pointer',
                'filename': 'data/pointer.txt',
                'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
            },
        ]
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    (port_handles, timestamps, framenumbers, tracking,
     quality) = tracker.get_frame()
    print(port_handles)
    assert len(port_handles) == len(timestamps)
    assert len(port_handles) == len(framenumbers)
    assert len(port_handles) == len(tracking)
    assert len(port_handles) == len(quality)
    assert len(port_handles) == 5
    assert 'reference' in port_handles
    assert 'bad_pointer' in port_handles
    assert 'good_pointer' in port_handles
    assert 'DICT_4X4_50:0' in port_handles

    ref_regression = np.array([[1., 0., 0., 135.38637], [0., 1., 0., 272.5],
                               [0., 0., 1., -57.1915], [0., 0., 0., 1.]],
                              dtype=np.float32)

    pointer_index = port_handles.index('bad_pointer')
    assert np.all(np.isnan(tracking[pointer_index][0:3, 0:4]))

    reference_index = port_handles.index('reference')
    assert np.allclose(tracking[reference_index], ref_regression)
def test_getframe_no_tracking():
    """
    Tests that value error is thrown when get frame called without tracking.
    reqs:
    """
    config = {'video source': 'data/output.avi'}

    tracker = ArUcoTracker(config)
    with pytest.raises(ValueError):
        (_port_handles, _timestamps, _framenumbers, _tracking,
         _quality) = tracker.get_frame()
    tracker.close()
def test_get_tool_descriptions():
    """
    Tests that get too descriptions.
    If no tool descriptions have been set it should return
    "No tools defined", otherwise it should return a list of
    tool names
    reqs:
    """
    config = {'video source': 'data/output.avi'}

    tracker = ArUcoTracker(config)
    assert tracker.get_tool_descriptions() == "No tools defined"
    tracker.close()
Пример #8
0
def run_demo(tracked, dicom_dir):
    """ Demo """
    app = QtWidgets.QApplication([])

    if tracked:
        tracker = ArUcoTracker({})
        tracker.start_tracking()

        slice_viewer = TrackedSliceViewer(dicom_dir, tracker)

    else:
        slice_viewer = MouseWheelSliceViewer(dicom_dir)

    slice_viewer.start()

    app.exec_()
def test_with_no_tags_and_calib():
    """
    connect track and close with multitags, defined
    rigid bodies, but no tags
    visible, should return an NaN matrix for each
    undetected body
    reqs: 03, 04 ,05, 07
    """
    config = {
        'calibration':
        'data/calibration.txt',
        'video source':
        'none',
        'rigid bodies': [{
            'name': 'reference',
            'filename': 'data/reference.txt',
            'aruco dictionary': 'DICT_4X4_50'
        }, {
            'name': 'pointer',
            'filename': 'data/pointer.txt',
            'aruco dictionary': 'DICT_4X4_50'
        }]
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()
    image = np.zeros((640, 480, 3), dtype=np.uint8)
    (port_handles, timestamps, framenumbers, tracking,
     quality) = tracker.get_frame(image)
    assert len(port_handles) == len(timestamps)
    assert len(port_handles) == len(framenumbers)
    assert len(port_handles) == len(tracking)
    assert len(port_handles) == len(quality)
    assert len(port_handles) == 2
    assert 'reference' in port_handles
    assert 'pointer' in port_handles

    reference_index = port_handles.index('reference')
    pointer_index = port_handles.index('pointer')

    assert quality[reference_index] == 0
    assert quality[pointer_index] == 0

    assert np.all(np.isnan(tracking[reference_index][0:3, 0:4]))
    assert np.all(np.isnan(tracking[pointer_index][0:3, 0:4]))

    tracker.stop_tracking()
    tracker.close()
def test_start_tracking_throws():
    """
    Tests that value error is thrown when start tracking called when not ready.
    reqs:
    """
    config = {'video source': 'data/12markers.avi'}
    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    with pytest.raises(ValueError):
        tracker.start_tracking()

    tracker.close()
def test_throw_on_bad_source():
    """
    Tests that OS error is thrown when an invalid source is used.,
    reqs:
    """
    config = {
        'video source': 'data/nofile.xxxx',
        'aruco dictionary': 'DICT_6X6_250'
    }

    with pytest.raises(OSError):
        _tracker = ArUcoTracker(config)
def test_invalid_dictionary():
    """
    Tests that Import error is thrown when an invalid aruco dictionary is used.
    reqs:
    """
    config = {
        'video source': 'data/12markers.avi',
        'aruco dictionary': 'DICT_7X6_250'
    }

    with pytest.raises(ImportError):
        _tracker = ArUcoTracker(config)
def test_throw_on_bad_calibration():
    """
    Tests that Value error is thrown when an invalid calibration is used.
    reqs:
    """
    config = {
        'video source': 'data/output.avi',
        'calibration': 'data/bad_calibration.txt'
    }

    with pytest.raises(ValueError):
        _tracker = ArUcoTracker(config)
Пример #14
0
    def __init__(self, image_source):
        """override the default constructor to set up sksurgeryarucotracker"""

        #we'll use SciKit-SurgeryArUcoTracker to estimate the pose of the
        #visible ArUco tag relative to the camera. We use a dictionary to
        #configure SciKit-SurgeryArUcoTracker

        ar_config = {
            "tracker type":
            "aruco",
            #Set to none, to share video source with OverlayBaseApp
            "video source":
            'none',
            "debug":
            False,
            #the aruco tag dictionary to use. DICT_4X4_50 will work with
            #../tags/aruco_4by4_0.pdf
            "dictionary":
            'DICT_4X4_50',
            "marker size":
            50,  # in mm
            #We need a calibrated camera. For now let's just use a
            #a hard coded estimate. Maybe you could improve on this.
            "camera projection":
            numpy.array(
                [[560.0, 0.0, 320.0], [0.0, 560.0, 240.0], [0.0, 0.0, 1.0]],
                dtype=numpy.float32),
            "camera distortion":
            numpy.zeros((1, 4), numpy.float32)
        }
        self.tracker = ArUcoTracker(ar_config)
        self.tracker.start_tracking()

        #and call the constructor for the base class
        if sys.version_info > (3, 0):
            super().__init__(image_source)
        else:
            #super doesn't work the same in py2.7
            OverlayBaseApp.__init__(self, image_source)
def test_no_video_no_tag():
    """
    no errors when no tags detected
    works on static images
    reqs: 03, 04 ,05
    """
    config = {'video source': 'none'}

    tracker = ArUcoTracker(config)
    tracker.start_tracking()
    image = np.zeros((640, 480, 3), dtype=np.uint8)
    (port_handles, timestamps, framenumbers, tracking,
     quality) = tracker.get_frame(image)
    assert len(port_handles) == len(timestamps)
    assert len(port_handles) == len(framenumbers)
    assert len(port_handles) == len(tracking)
    assert len(port_handles) == len(quality)
    assert len(port_handles) == 0

    tracker.stop_tracking()
    tracker.close()
def test_setting_capture_properties():
    """
    connect track and close with multi tag,
    reqs: 03, 04 ,05, 07
    """
    config = {
        'video source': 'data/12markers.avi',
        'aruco dictionary': 'DICT_6X6_250',
        "capture properties": {
            "CAP_PROP_FRAME_WIDTH": 1280,
            "CAP_PROP_FRAME_HEIGHT": 1024
        }
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    (_port_handles, _timestamps, _framenumbers, _tracking,
     _quality) = tracker.get_frame()

    tracker.stop_tracking()
    tracker.close()
def test_on_video_with_single_tag():
    """
    connect track and close with single tag,
    reqs: 03, 04 ,05
    """
    config = {'video source': 'data/output.avi'}

    tracker = ArUcoTracker(config)
    tracker.start_tracking()
    for frame in range(10):
        (port_handles, timestamps, framenumbers, tracking,
         quality) = tracker.get_frame()
        assert len(port_handles) == len(timestamps)
        assert len(port_handles) == len(framenumbers)
        assert len(port_handles) == len(tracking)
        assert len(port_handles) == len(quality)
        assert len(port_handles) == 1
        assert port_handles[0] == 'DICT_4X4_50:0'
        assert framenumbers[0] == frame
        assert quality[0] == 1.0

    tracker.stop_tracking()
    tracker.close()
Пример #18
0
def configure_tracker(config):
    """
    Configures the tracking system.
    :param: A dictionary containing configuration data
    :return: The tracker object
    :raises: KeyError if no tracker entry in config
    """
    if "tracker type" not in config:
        raise KeyError('Tracker configuration requires tracker type')

    tracker_type = config.get("tracker type")
    tracker = None
    if tracker_type in ("vega", "polaris", "aurora", "dummy"):
        tracker = NDITracker(config)
    if tracker_type in "aruco":
        tracker = ArUcoTracker(config)

    tracker.start_tracking()
    return tracker
Пример #19
0
def configure_tracker(config):
    """
    Configures a scikit-surgery tracker based on the passed config

    :param config: a tracker configuration dictionary
    :returns: The tracker
    :raises: KeyError
    """

    if "tracker type" not in config:
        raise KeyError('Tracker configuration requires tracker type')

    tracker_type = config.get("tracker type")
    tracker = None
    if tracker_type in ("vega", "polaris", "aurora", "dummy"):
        tracker = NDITracker(config)
    if tracker_type in "aruco":
        tracker = ArUcoTracker(config)

    if tracker_type not in "dummy":
        tracker.start_tracking()
    return tracker
def test_vs_solve_pnp_singletag():
    """
    This checks whether the tracking result using skarucotracker
    matches that when using the solvePnP approach as originally
    implemented by scikit-surgeryBARAD, with the addition of
    tracking smoothing
    """
    calib_mtx = np.array([[608.67179504, 0.00000000, 323.12263928],
                          [0.00000000, 606.13421375, 231.29247171],
                          [0.0, 0.0, 1.0]], dtype = np.float64)
    distortion = np.array([-0.02191634, -0.14300148, -0.00395124,
                           -0.00044941, 0.19656551], dtype = np.float64)
    videofile = 'data/output.avi'

    config = {'video source' : 'none',
              'camera projection' : calib_mtx,
              'camera distortion' : distortion,
              'aruco dictionary' : 'DICT_ARUCO_ORIGINAL',
              'smoothing buffer' : 5,
              'rigid bodies' : [
                      {
                        'name' : 'reference',
                        'filename' : 'data/tag_0.txt',
                        'aruco dictionary' : 'DICT_4X4_50'
                      }
                      ]
              }

    config2 = {'video source' : 'none',
              'camera projection' : calib_mtx,
              'camera distortion' : distortion,
              'aruco dictionary' : 'DICT_4X4_50',
              'marker size' : 33,
              'smoothing buffer' : 5,
              }


    capture = cv.VideoCapture(videofile)
    #set up skarucotracker
    tracker = ArUcoTracker(config)
    tracker.start_tracking()
    tracker2 = ArUcoTracker(config2)
    tracker2.start_tracking()

    #set up solvepnp
    three_d_points = np.loadtxt('data/tag_0.txt')
    three_d_points = three_d_points.reshape(1, 16)
    three_d_points = ccw_to_cw(three_d_points)

    reference_register = Registration2D3D(three_d_points,
                                          calib_mtx, distortion,
                                          buffer_size=5)

    for _frame in range(10):
        _, image = capture.read()
        (port_handles, _timestamps, _framenumbers,
        tracking, _quality) = tracker.get_frame(image)

        assert 'reference' in port_handles
        reference_index = port_handles.index('reference')

        aruco_reference_tracking = tracking[reference_index]

        (port_handles, _timestamps, _framenumbers,
        tracking, _quality) = tracker2.get_frame(image)

        assert 'DICT_4X4_50:0' in port_handles
        reference_index = port_handles.index('DICT_4X4_50:0')

        aruco_reference_tracking2= tracking[reference_index]

        #now try again using our own implementation using cv.solvepnp as
        #formerly implemented in BARD
        marker_corners, ids, _ = aruco.detectMarkers(image,
                       aruco.getPredefinedDictionary(
                                aruco.DICT_4X4_50))

        success, modelreference2camera = \
                    reference_register.get_matrix(
                        ids, marker_corners)
        assert success
        assert np.allclose(modelreference2camera, aruco_reference_tracking)
        assert np.allclose(aruco_reference_tracking2, aruco_reference_tracking)

    tracker.stop_tracking()
    tracker.close()
    capture.release()
def test_arucotracker_vs_solve_pnp():
    """
    This checks whether the tracking result using skarucotracker
    matches that when using the solvePnP approach as originally
    implemented by scikit-surgeryBARD
    """
    calib_mtx = np.array([[608.67179504, 0.00000000, 323.12263928],
                          [0.00000000, 606.13421375, 231.29247171],
                          [0.0, 0.0, 1.0]], dtype = np.float64)
    distortion = np.array([-0.02191634, -0.14300148, -0.00395124,
                           -0.00044941, 0.19656551], dtype = np.float64)
    videofile = 'data/multipattern.avi'

    config = {'video source' : 'none',
              'camera projection' : calib_mtx,
              'camera distortion' : distortion,
              'aruco dictionary' : 'DICT_ARUCO_ORIGINAL',
              'rigid bodies' : [
                      {
                        'name' : 'reference',
                        'filename' : 'data/reference.txt',
                        'aruco dictionary' : 'DICT_ARUCO_ORIGINAL'
                      }
                      ]
              }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()
    capture = cv.VideoCapture(videofile)
    _, image = capture.read()
    (port_handles, _timestamps, _framenumbers,
     tracking, quality) = tracker.get_frame(image)

    assert 'reference' in port_handles

    reference_index = port_handles.index('reference')

    assert np.isclose(quality[reference_index], 0.91666666)

    ref_regression = np.array([
       [-0.85007277,  0.51807849, -0.09471516, -8.06235428e+01],
       [-0.46167221, -0.64647658,  0.60739345, 5.07177658e+01],
       [ 0.25344635,  0.56005599,  0.78873458, 2.50268387e+02],
       [ 0.0000e+00, 0.00000e+00, 0.00000e+00, 1.00000000e+00]],
       dtype=np.float32)


    aruco_reference_tracking = tracking[reference_index]
    assert np.allclose(aruco_reference_tracking, ref_regression)

    tracker.stop_tracking()
    tracker.close()

    #now try again using our own implementation using cv.solvepnp as
    #formerly implemented in BARD
    three_d_points = np.loadtxt('data/reference.txt')

    reference_register = Registration2D3D(three_d_points,
                                          calib_mtx, distortion,
                                          buffer_size=1)

    marker_corners, ids, _ = aruco.detectMarkers(image,
                    aruco.getPredefinedDictionary(
                            aruco.DICT_ARUCO_ORIGINAL))

    success, modelreference2camera = \
                reference_register.get_matrix(
                    ids, marker_corners)

    assert success
    assert np.allclose(modelreference2camera, ref_regression)

    capture.release()
def test_tool_desc_and_float64():
    """
    connect track and close with multitags, defined
    rigid bodies, and camera calibration, defined with
    different data types, issue #31
    reqs: 03, 04 ,05, 07
    """
    config = {
        'video source':
        'data/multipattern.avi',
        'calibration':
        'data/calibration.txt',
        'aruco dictionary':
        'DICT_ARUCO_ORIGINAL',
        'rigid bodies': [
            {
                'name': 'reference',
                'filename': 'data/reference.txt',
                'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
            },
        ]
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    (port_handles, _timestamps, _framenumbers, tracking,
     quality) = tracker.get_frame()
    assert 'reference' in port_handles

    reference_index = port_handles.index('reference')

    assert np.isclose(quality[reference_index], 0.91666666)

    ref_regression = np.array(
        [[-0.84701057, 0.51884094, -0.11565978, -8.22903442e+01],
         [-0.48733129, -0.67100208, 0.55880625, 4.85032501e+01],
         [0.21232361, 0.52967943, 0.82119327, 2.43992401e+02],
         [0.00000000e+00, 0.00000000e+00, 0.00000000e+00, 1.00000000e+00]],
        dtype=np.float32)

    assert np.allclose(tracking[reference_index], ref_regression)

    tracker.stop_tracking()
    tracker.close()
    port_handles = None
    tracking = None
    quality = None

    #again, but this time set calibration and distortion separately
    calib_mtx = np.array(
        [[560.0, 0.0, 320.0], [0.0, 560.0, 240.0], [0.0, 0.0, 1.0]],
        dtype=np.float32)
    distortion = np.array([0.1, 0.0, 0.0, 0.0, 0.0], dtype=np.float32)
    config = {
        'video source':
        'data/multipattern.avi',
        'camera projection':
        calib_mtx,
        'camera distortion':
        distortion,
        'aruco dictionary':
        'DICT_ARUCO_ORIGINAL',
        'rigid bodies': [
            {
                'name': 'reference',
                'filename': 'data/reference.txt',
                'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
            },
        ]
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    (port_handles, _timestamps, _framenumbers, tracking,
     quality) = tracker.get_frame()
    assert 'reference' in port_handles

    reference_index = port_handles.index('reference')

    assert np.isclose(quality[reference_index], 0.91666666)
    assert np.allclose(tracking[reference_index], ref_regression)

    tracker.stop_tracking()
    tracker.close()
    port_handles = None
    tracking = None
    quality = None

    #again, but this time set calibration and distortion as float64
    calib_mtx = np.array(
        [[560.0, 0.0, 320.0], [0.0, 560.0, 240.0], [0.0, 0.0, 1.0]],
        dtype=np.float64)
    distortion = np.array([0.1, 0.0, 0.0, 0.0, 0.0], dtype=np.float64)
    config = {
        'video source':
        'data/multipattern.avi',
        'camera projection':
        calib_mtx,
        'camera distortion':
        distortion,
        'aruco dictionary':
        'DICT_ARUCO_ORIGINAL',
        'rigid bodies': [
            {
                'name': 'reference',
                'filename': 'data/reference.txt',
                'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
            },
        ]
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    (port_handles, _timestamps, _framenumbers, tracking,
     quality) = tracker.get_frame()
    assert 'reference' in port_handles

    reference_index = port_handles.index('reference')

    assert np.isclose(quality[reference_index], 0.91666666)
    assert np.allclose(tracking[reference_index], ref_regression)

    tracker.stop_tracking()
    tracker.close()
    port_handles = None
    tracking = None
    quality = None

    #again, but this time set calibration and distortion as float
    calib_mtx = np.array(
        [[560.0, 0.0, 320.0], [0.0, 560.0, 240.0], [0.0, 0.0, 1.0]],
        dtype=float)
    distortion = np.array([0.1, 0.0, 0.0, 0.0, 0.0], dtype=float)
    config = {
        'video source':
        'data/multipattern.avi',
        'camera projection':
        calib_mtx,
        'camera distortion':
        distortion,
        'aruco dictionary':
        'DICT_ARUCO_ORIGINAL',
        'rigid bodies': [
            {
                'name': 'reference',
                'filename': 'data/reference.txt',
                'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
            },
        ]
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    (port_handles, _timestamps, _framenumbers, tracking,
     quality) = tracker.get_frame()
    assert 'reference' in port_handles

    reference_index = port_handles.index('reference')

    assert np.isclose(quality[reference_index], 0.91666666)
    assert np.allclose(tracking[reference_index], ref_regression)

    tracker.stop_tracking()
    tracker.close()
def test_with_tool_descriptions():
    """
    connect track and close with multitags and defined
    rigid bodies,
    reqs: 03, 04 ,05, 07
    """
    #test first with no tool descriptions
    config = {'video source': 'data/multipattern.avi'}

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    #with nothing set we'll only detect tag ID 0, the others
    #are from a different dictionary.
    (port_handles, timestamps, framenumbers, tracking,
     quality) = tracker.get_frame()
    assert len(port_handles) == len(timestamps)
    assert len(port_handles) == len(framenumbers)
    assert len(port_handles) == len(tracking)
    assert len(port_handles) == len(quality)
    assert len(port_handles) == 1
    assert 'DICT_4X4_50:0' in port_handles

    tracker.stop_tracking()
    tracker.close()

    #try again with the right dictionary for the bard marker tags
    config = {
        'video source': 'data/multipattern.avi',
        'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    #with nothing set we'll only detect tag ID 0, the others
    #are from a different dictionary.
    (port_handles, timestamps, framenumbers, tracking,
     quality) = tracker.get_frame()
    assert len(port_handles) == len(timestamps)
    assert len(port_handles) == len(framenumbers)
    assert len(port_handles) == len(tracking)
    assert len(port_handles) == len(quality)
    assert len(port_handles) == 17
    assert 'DICT_ARUCO_ORIGINAL:1' in port_handles

    #we should load the tag info and check that all tags are found
    tracker.stop_tracking()
    tracker.close()

    config = {
        'video source':
        'data/multipattern.avi',
        'rigid bodies': [{
            'name': 'reference',
            'filename': 'data/reference.txt',
            'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
        }, {
            'name': 'pointer',
            'filename': 'data/pointer.txt',
            'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
        }]
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    (port_handles, timestamps, framenumbers, tracking,
     quality) = tracker.get_frame()
    assert len(port_handles) == len(timestamps)
    assert len(port_handles) == len(framenumbers)
    assert len(port_handles) == len(tracking)
    assert len(port_handles) == len(quality)
    assert len(port_handles) == 4  #there is an extraneous marker (1000)
    assert 'reference' in port_handles
    assert 'pointer' in port_handles
    assert 'DICT_4X4_50:0' in port_handles

    reference_index = port_handles.index('reference')

    ref_regression = np.array([[1., 0., 0., 135.38637], [0., 1., 0., 272.5],
                               [0., 0., 1., -57.1915], [0., 0., 0., 1.]],
                              dtype=np.float32)

    assert np.allclose(tracking[reference_index], ref_regression)
    assert np.isclose(quality[reference_index], 0.91666666)
    pointer_index = port_handles.index('pointer')
    assert np.isclose(quality[pointer_index], 0.83333333)

    tracker.stop_tracking()
    tracker.close()

    #check that tag 0 is not detected when we use only
    #DICT_ARUCO_ORIGINAL
    config = {
        'video source':
        'data/multipattern.avi',
        'aruco dictionary':
        'DICT_ARUCO_ORIGINAL',
        'rigid bodies': [{
            'name': 'reference',
            'filename': 'data/reference.txt',
            'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
        }, {
            'name': 'pointer',
            'filename': 'data/pointer.txt',
            'aruco dictionary': 'DICT_ARUCO_ORIGINAL'
        }]
    }

    tracker = ArUcoTracker(config)
    tracker.start_tracking()

    (port_handles, timestamps, framenumbers, tracking,
     quality) = tracker.get_frame()
    assert len(port_handles) == len(timestamps)
    assert len(port_handles) == len(framenumbers)
    assert len(port_handles) == len(tracking)
    assert len(port_handles) == len(quality)
    assert len(port_handles) == 3  #there is an extraneous marker (1000)
    assert 'reference' in port_handles
    assert 'pointer' in port_handles
    assert 'DICT_4X4_50:0' not in port_handles
Пример #24
0
class OverlayApp(OverlayBaseApp):
    """Inherits from OverlayBaseApp, and adds methods to
    detect aruco tags and move the model to follow."""
    def __init__(self, image_source):
        """override the default constructor to set up sksurgeryarucotracker"""

        #we'll use SciKit-SurgeryArUcoTracker to estimate the pose of the
        #visible ArUco tag relative to the camera. We use a dictionary to
        #configure SciKit-SurgeryArUcoTracker

        ar_config = {
            "tracker type":
            "aruco",
            #Set to none, to share video source with OverlayBaseApp
            "video source":
            'none',
            "debug":
            False,
            #the aruco tag dictionary to use. DICT_4X4_50 will work with
            #../tags/aruco_4by4_0.pdf
            "dictionary":
            'DICT_4X4_50',
            "marker size":
            50,  # in mm
            #We need a calibrated camera. For now let's just use a
            #a hard coded estimate. Maybe you could improve on this.
            "camera projection":
            numpy.array(
                [[560.0, 0.0, 320.0], [0.0, 560.0, 240.0], [0.0, 0.0, 1.0]],
                dtype=numpy.float32),
            "camera distortion":
            numpy.zeros((1, 4), numpy.float32)
        }
        self.tracker = ArUcoTracker(ar_config)
        self.tracker.start_tracking()

        #and call the constructor for the base class
        if sys.version_info > (3, 0):
            super().__init__(image_source)
        else:
            #super doesn't work the same in py2.7
            OverlayBaseApp.__init__(self, image_source)

    def update(self):
        """Update the background render with a new frame and
        scan for aruco tags"""
        _, image = self.video_source.read()
        self._aruco_detect_and_follow(image)

        #Without the next line the model does not show as the clipping range
        #does not change to accommodate model motion. Uncomment it to
        #see what happens.
        self.vtk_overlay_window.set_camera_state({"ClippingRange": [10, 800]})
        self.vtk_overlay_window.set_video_image(image)
        self.vtk_overlay_window.Render()

    def _aruco_detect_and_follow(self, image):
        """Detect any aruco tags present using sksurgeryarucotracker
        """

        #tracker.get_frame(image) returns 5 lists of tracking data.
        #we'll only use the tracking matrices (tag2camera)
        _port_handles, _timestamps, _frame_numbers, tag2camera, \
                        _tracking_quality = self.tracker.get_frame(image)

        if tag2camera is not None:
            #pass the first entry in tag2camera. If you have more than one tag
            #visible, you may need to do something cleverer here.
            self._move_camera(tag2camera[0])

    def _move_camera(self, tag2camera):
        """Internal method to move the rendered models in
        some interesting way"""

        #SciKit-SurgeryCore has a useful TransformManager that makes
        #chaining together and inverting transforms more intuitive.
        #We'll just use it to invert a matrix here.
        transform_manager = TransformManager()
        transform_manager.add("tag2camera", tag2camera)
        camera2tag = transform_manager.get("camera2tag")

        #Let's move the camera, rather than the model this time.
        self.vtk_overlay_window.set_camera_pose(camera2tag)
def test_no_video_single_tag():
    """
    raises a value error when no video and no image passed.
    works on static images
    reqs: 03, 04 ,05
    """
    config = {'video source': 'none'}

    tracker = ArUcoTracker(config)
    assert not tracker.has_capture()
    tracker.start_tracking()
    with pytest.raises(ValueError):
        tracker.get_frame()
    capture = VideoCapture('data/output.avi')
    for frame in range(2):
        _, image = capture.read()
        (port_handles, timestamps, framenumbers, tracking,
         quality) = tracker.get_frame(image)
        assert len(port_handles) == len(timestamps)
        assert len(port_handles) == len(framenumbers)
        assert len(port_handles) == len(tracking)
        assert len(port_handles) == len(quality)
        assert len(port_handles) == 1
        assert port_handles[0] == 'DICT_4X4_50:0'
        assert framenumbers[0] == frame
        assert quality[0] == 1.0

    tracker.stop_tracking()
    tracker.close()