diff --git a/.github/workflows/CI.yml b/.github/workflows/CI.yml index 166aef7..d5851b0 100644 --- a/.github/workflows/CI.yml +++ b/.github/workflows/CI.yml @@ -18,8 +18,25 @@ jobs: julia-version: ['1.9', '~1.10.0-0', 'nightly'] os: [ubuntu-latest] arch: [x64] + # https://github.com/ros-tooling/action-ros-ci/blob/master/.github/workflows/test.yml + ros_distribution: + - noetic + include: + # Noetic Ninjemys (May 2020 - May 2025) + - docker_image: rostooling/setup-ros-docker:ubuntu-focal-ros-noetic-ros-base-latest + ros_distribution: noetic steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v4 + - uses: actions/setup-python@v4 + # with: + # python-version: '3.9' + # cache: 'pip' + # - run: pip install opencv-python + # - uses: ros-tooling/setup-ros@v0.7 + # with: + # required-ros-distributions: noetic + # - run: "source /opt/ros/noetic/setup.bash" + # docker pull osrf/ros:noetic-desktop - uses: julia-actions/setup-julia@v1 with: version: ${{ matrix.julia-version }} diff --git a/Project.toml b/Project.toml index 605ebf6..e206233 100644 --- a/Project.toml +++ b/Project.toml @@ -7,17 +7,24 @@ version = "0.1.0" [deps] Caesar = "62eebf14-49bc-5f46-9df9-f7b7ef379406" Dates = "ade2ca70-3891-5945-98fb-dc099432e06a" +DistributedFactorGraphs = "b5cc3c7e-6572-11e9-2517-99fb8daf2f04" DocStringExtensions = "ffbed154-4ef7-542d-bbb7-c09d3a79fcae" +JSON3 = "0f8b85d8-7281-11e9-16c2-39a750bddbf1" Pkg = "44cfe95a-1eb2-52ea-b672-e2afdf69b78f" +ProgressMeter = "92933f4c-e287-5a05-a399-4b506db050ca" PyCall = "438e738f-606a-5dbb-bf0a-cddfbfd45ab0" +SHA = "ea8e919c-243c-51af-8825-aaa63cd721ce" +TensorCast = "02d47bb6-7ce6-556a-be16-bb1710789e2b" UUIDs = "cf7118a7-6976-5b1a-9a39-7adc72f591a4" Unmarshal = "cbff2730-442d-58d7-89d1-8e530c41eb02" [weakdeps] RobotOS = "22415677-39a4-5241-a37a-00beabbbdae8" +Images = "916415d5-f1e6-5110-898d-aaa5f9f070e0" [extensions] PyCaesarRobotOSExt = "RobotOS" +PyCaesarImagesExt = "Images" [compat] Caesar = "0.15, 0.16" @@ -29,6 +36,7 @@ julia = "1.9" [extras] Test = "8dfed614-e22c-5e08-85e1-65c5234f0b40" +TestImages = "5e47fb64-e119-507b-a336-dd2b206d9990" [targets] -test = ["RobotOS", "Test"] +test = ["RobotOS", "Test", "TestImages"] diff --git a/README.md b/README.md new file mode 100644 index 0000000..96572f9 --- /dev/null +++ b/README.md @@ -0,0 +1,38 @@ +# PyCaesar.jl + +| Stable | Dev | Coverage | Docs | +|--------|-----|----------|------| +| [![version][pycjl-ver-img]][pycjl-releases] | [![CI][pycjl-ci-dev-img]][pycjl-ci-dev-url] | [![codecov.io][pycjl-cov-img]][pycjl-cov-url] | [![docs][cjl-docs-img]][cjl-docs-url]
[![][caesar-slack-badge]][caesar-slack] | + +## Dependencies + +The following packages should be available in the Python environment used by PyCall.jl + +``` +rospy +opencv-python # i.e. cv2 +open3d +Rosbags +``` + +> 23Q3: We had issues in using Conda.jl to install these dependecies in a new environment, specifically conda package compliance with newer versions of Python. E.g. open3d was not available via conda on Python 3.10 at the time of writing. Please open an issue if further clarification is needed. + +## Introduction + +Caesar.jl extensions using Python. See common [Caesar.jl][cjl-docs-url] Docs for details. + + +[pycjl-url]: http://www.github.com/JuliaRobotics/PyCaesar.jl +[pycjl-cov-img]: https://codecov.io/github/JuliaRobotics/PyCaesar.jl/coverage.svg?branch=develop +[pycjl-cov-url]: https://codecov.io/github/JuliaRobotics/PyCaesar.jl?branch=develop +[pycjl-ci-dev-img]: https://github.com/JuliaRobotics/PyCaesar.jl/actions/workflows/CI.yml/badge.svg +[pycjl-ci-dev-url]: https://github.com/JuliaRobotics/PyCaesar.jl/actions/workflows/CI.yml +[pycjl-ver-img]: https://juliahub.com/docs/PyCaesar/version.svg +[pycjl-milestones]: https://github.com/JuliaRobotics/PyCaesar.jl/milestones +[pycjl-releases]: https://github.com/JuliaRobotics/PyCaesar.jl/releases + +[cjl-url]: https://github.com/JuliaRobotics/Caesar.jl +[cjl-docs-img]: https://img.shields.io/badge/docs-latest-blue.svg +[cjl-docs-url]: http://juliarobotics.github.io/Caesar.jl/latest/ +[caesar-slack-badge]: https://img.shields.io/badge/Caesarjl-Slack-green.svg?style=popout +[caesar-slack]: https://join.slack.com/t/caesarjl/shared_invite/zt-ucs06bwg-y2tEbddwX1vR18MASnOLsw \ No newline at end of file diff --git a/ext/PyCaesarImagesExt.jl b/ext/PyCaesarImagesExt.jl new file mode 100644 index 0000000..c12fb39 --- /dev/null +++ b/ext/PyCaesarImagesExt.jl @@ -0,0 +1,38 @@ +module PyCaesarImagesExt + +using PyCall +using Images +# using PyCaesars +# using ImageFeatures +using DistributedFactorGraphs +using ProgressMeter +using JSON3 +using TensorCast +using SHA: sha256 + +import PyCaesar: calcFlow, getPose, goodFeaturesToTrack, goodFeaturesToTrackORB, combinePlot +import PyCaesar: trackFeaturesFrames, trackFeaturesForwardsBackwards, makeBlobFeatureTracksPerImage_FwdBck!, makeORBParams, plotBlobsImageTracks! +import PyCaesar: whatcv + +export calcFlow, getPose, goodFeaturesToTrack, goodFeaturesToTrackORB, combinePlot +export trackFeaturesFrames, trackFeaturesForwardsBackwards, makeBlobFeatureTracksPerImage_FwdBck!, makeORBParams, plotBlobsImageTracks! + + +const np = PyNULL() +const cv = PyNULL() + +function __init__() + copy!(np, pyimport("numpy")) + copy!(cv, pyimport("cv2")) +end + +pyutilpath = joinpath(@__DIR__, "Utils") +pushfirst!(PyVector(pyimport("sys")."path"), pyutilpath ) + +SscPy = pyimport("PySSCFeatures") +ssc = SscPy."ssc" + + +include("services/OpenCVFeatures.jl") + +end \ No newline at end of file diff --git a/ext/Utils/PySSCFeatures.py b/ext/Utils/PySSCFeatures.py new file mode 100644 index 0000000..78f57d5 --- /dev/null +++ b/ext/Utils/PySSCFeatures.py @@ -0,0 +1,131 @@ +# Taken from: https://github.com/BAILOOL/ANMS-Codes/blob/568fa6a1b39aa46fa04ad600cb40a33decf52897/Python/ssc.py#L1 + +# @article{bailo2018efficient, +# title={Efficient adaptive non-maximal suppression algorithms for homogeneous spatial keypoint distribution}, +# author={Bailo, Oleksandr and Rameau, Francois and Joo, Kyungdon and Park, Jinsun and Bogdan, Oleksandr and Kweon, In So}, +# journal={Pattern Recognition Letters}, +# volume={106}, +# pages={53--60}, +# year={2018}, +# publisher={Elsevier} +# } + +# MIT "Expat" License + +# Copyright (c) 2018 Oleksandr Bailo + +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: + +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. + +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. + + +import math + +def ssc(keypoints, num_ret_points, tolerance, cols, rows): + exp1 = rows + cols + 2 * num_ret_points + exp2 = ( + 4 * cols + + 4 * num_ret_points + + 4 * rows * num_ret_points + + rows * rows + + cols * cols + - 2 * rows * cols + + 4 * rows * cols * num_ret_points + ) + exp3 = math.sqrt(exp2) + exp4 = num_ret_points - 1 + + sol1 = -round(float(exp1 + exp3) / exp4) # first solution + sol2 = -round(float(exp1 - exp3) / exp4) # second solution + + high = ( + sol1 if (sol1 > sol2) else sol2 + ) # binary search range initialization with positive solution + low = math.floor(math.sqrt(len(keypoints) / num_ret_points)) + + prev_width = -1 + selected_keypoints = [] + result_list = [] + result = [] + complete = False + k = num_ret_points + k_min = round(k - (k * tolerance)) + k_max = round(k + (k * tolerance)) + + while not complete: + width = low + (high - low) / 2 + if ( + width == prev_width or low > high + ): # needed to reassure the same radius is not repeated again + result_list = result # return the keypoints from the previous iteration + break + + c = width / 2 # initializing Grid + num_cell_cols = int(math.floor(cols / c)) + num_cell_rows = int(math.floor(rows / c)) + covered_vec = [ + [False for _ in range(num_cell_cols + 1)] for _ in range(num_cell_rows + 1) + ] + result = [] + + for i in range(len(keypoints)): + row = int( + math.floor(keypoints[i].pt[1] / c) + ) # get position of the cell current point is located at + col = int(math.floor(keypoints[i].pt[0] / c)) + if not covered_vec[row][col]: # if the cell is not covered + result.append(i) + # get range which current radius is covering + row_min = int( + (row - math.floor(width / c)) + if ((row - math.floor(width / c)) >= 0) + else 0 + ) + row_max = int( + (row + math.floor(width / c)) + if ((row + math.floor(width / c)) <= num_cell_rows) + else num_cell_rows + ) + col_min = int( + (col - math.floor(width / c)) + if ((col - math.floor(width / c)) >= 0) + else 0 + ) + col_max = int( + (col + math.floor(width / c)) + if ((col + math.floor(width / c)) <= num_cell_cols) + else num_cell_cols + ) + for row_to_cover in range(row_min, row_max + 1): + for col_to_cover in range(col_min, col_max + 1): + if not covered_vec[row_to_cover][col_to_cover]: + # cover cells within the square bounding box with width w + covered_vec[row_to_cover][col_to_cover] = True + + if k_min <= len(result) <= k_max: # solution found + result_list = result + complete = True + elif len(result) < k_min: + high = width - 1 # update binary search range + else: + low = width + 1 + prev_width = width + + for i in range(len(result_list)): + selected_keypoints.append(keypoints[result_list[i]]) + + return selected_keypoints diff --git a/ext/Utils/RosbagSubscriber.jl b/ext/Utils/RosbagSubscriber.jl index 53fd7a1..2cc78cd 100644 --- a/ext/Utils/RosbagSubscriber.jl +++ b/ext/Utils/RosbagSubscriber.jl @@ -17,13 +17,13 @@ writeRosbagPy = pyimport("rosbagWriter") ```julia # Link with ROSbag infrastructure via rospy -using Pkg -ENV["PYTHON"] = "/usr/bin/python3" -Pkg.build("PyCall") -using PyCall +# using Pkg +# ENV["PYTHON"] = "/usr/bin/python3" +# Pkg.build("PyCall") +# using PyCall using RobotOS @rosimport std_msgs.msg: String -rostypegen() +rostypegen(Main) # default defintion dump into Main using Caesar bagwr = Caesar.RosbagWriter("/tmp/test.bag") diff --git a/ext/services/OpenCVFeatures.jl b/ext/services/OpenCVFeatures.jl new file mode 100644 index 0000000..bf85462 --- /dev/null +++ b/ext/services/OpenCVFeatures.jl @@ -0,0 +1,271 @@ + + + +# # lk_params = ( winSize = (19, 19), maxLevel = 2, criteria = (cv.TERM_CRITERIA_EPS | cv.TERM_CRITERIA_COUNT, 10, 0.03)) +# lk_params = ( winSize = (19, 19), maxLevel = 2, criteria = (cv.TERM_CRITERIA_EPS | cv.TERM_CRITERIA_COUNT, 30, 0.01)) +# feature_params = (maxCorners = 1000, qualityLevel = 0.01, minDistance = 8, blockSize = 19 ) + +function calcFlow(jl_img0, jl_img1, p0, lk_params, back_threshold = 1.0) + # https://www.programcreek.com/python/example/89363/cv2.calcOpticalFlowPyrLK + img0 = collect(reinterpret(UInt8, jl_img0)) + img1 = collect(reinterpret(UInt8, jl_img1)) + status = zeros(UInt8, length(p0)) + p1, _st, _err = cv.calcOpticalFlowPyrLK(img0, img1, p0, nothing; lk_params...) + p0r, _st, _err = cv.calcOpticalFlowPyrLK(img1, img0, p1, nothing; lk_params...) + d = maximum(reshape(abs.(p0 .- p0r), :, 2); dims=2)#.reshape(-1, 2).max(-1) + status = d .< back_threshold + return p1, status +end + + +function getPose(p1, p2, K) + # Calculates an essential matrix from the corresponding points in two images. + E, essmat_mask = cv.findEssentialMat(p1, p2, K, cv.RANSAC, 0.999, 1.0, nothing) + # Recovers the relative camera rotation and the translation from an estimated + # essential matrix and the corresponding points in two images, using chirality check. + # Returns the number of inliers that pass the check. + rv, R, t, recpose_mask = cv.recoverPose(E, p1, p2, K, nothing) + return rv, R, t, recpose_mask +end + +function goodFeaturesToTrack(im1, feature_params; mask=nothing) + cv.goodFeaturesToTrack(collect(reinterpret(UInt8, im1)), mask=collect(reinterpret(UInt8,mask)), feature_params...) +end + +function goodFeaturesToTrackORB(im1; mask=nothing, orb = cv.ORB_create(), downsample::Int=1, tolerance::Real = 0.1) + # gray = cv2.cvtColor(im1,cv.COLOR_BGR2GRAY) + # kypts, decrs = orb.detectAndCompute(gray,None) + # https://docs.opencv.org/3.4/d1/d89/tutorial_py_orb.html + # find the keypoints with ORB + img = collect(reinterpret(UInt8, im1)) + kp = if isnothing(mask) + orb.detect(img) + else + orb.detect(img, collect(reinterpret(UInt8,mask))) + end + + sel_kp = if 1 < downsample + # downselect a better distribution of features + rows, cols = size(img,1), size(img,2) + ssc(kp, orb.getMaxFeatures() รท downsample, tolerance, cols, rows) + else + kp + end + + # compute the descriptors with ORB + kp_, des = orb.compute(img, sel_kp) + + return kp_, des +end + +function combinePlot(ref_img, overlay_img) + combine = map(zip(reinterpret(Gray{N0f8}, ref_img), reinterpret(Gray{N0f8}, overlay_img))) do (a,b) + RGB(a, b, a) + end + f = image(rotr90(combine), axis = (aspect = DataAspect(),)) + return f +end + +function getPose(im1, im2, K, feature_params, lk_params; mask=nothing) + + p1 = goodFeaturesToTrack(im1, feature_params; mask) + + p2, flow_status = calcFlow(im1, im2, p1, lk_params) + + # only keep good points + p1 = p1[flow_status, :, :] + p2 = p2[flow_status, :, :] + + rv, R, t, recpose_mask = getPose(p1, p2, K) + return rv, R, t, recpose_mask +end + + +function trackFeaturesFrames( + feats0, + jl_imgs0_n::AbstractVector{<:AbstractMatrix}, + lk_params; + mask = nothing +) + # https://www.programcreek.com/python/example/89363/cv2.calcOpticalFlowPyrLK + imgs = reinterpret.(UInt8, jl_imgs0_n) .|> collect + + tracks = [] + # status = zeros(UInt8, length(feats0)) + for (i,img) in enumerate(imgs) + # skip first image which is assumed to coincide with feats0 (good features on first frame) + i == 1 ? continue : nothing + p1, _st, _err = cv.calcOpticalFlowPyrLK(imgs[1], img, feats0, nothing; lk_params...) # collect(reinterpret(UInt8,mask)) + push!(tracks, p1) + end + + return tracks +end + + +function trackFeaturesForwardsBackwards(imgs, feature_params, lk_params; mask=nothing, orb = cv.ORB_create()) + + len = length(imgs) + @assert isodd(len) "expecting odd number of images for forward backward tracking from center image" + + cen = floor(Int, len/2) + 1 + + img_tracks = Dict{Int,Vector{Vector{Float64}}}() + dscs0 = Dict{Int,Tuple{Float64, Vector{Int}}}() + + # use orb /w descriptors || good features + feats0 = if true + kpts, dscs = goodFeaturesToTrackORB(imgs[cen]; mask, orb) + img_tracks[0] = [[kpts[k].pt[1];kpts[k].pt[2]] for k in 1:length(kpts)] + # legacy fill feats0 for tracking + feats0_ = zeros(Float32,length(kpts),1,2) + for k in 1:length(kpts) + feats0_[k,1,1] = kpts[k].pt[1] + feats0_[k,1,2] = kpts[k].pt[2] + dscs0[k] = (kpts[k].angle, Int.(dscs[k,:][:])) + end + feats0_ + else + feats0_ = goodFeaturesToTrack(imgs[cen], feature_params; mask) + img_tracks[0] = [feats0_[k,:,:][:] for k in 1:size(feats0_,1 )] + feats0_ + end + + tracks = trackFeaturesFrames(feats0, imgs[cen:end], lk_params; mask) + for (i,tr) in enumerate(tracks) + isnothing(tr) && continue + img_tracks[i] = [tr[k,:,:][:] for k in 1:size(tr,1)] + end + + tracks = trackFeaturesFrames(feats0, imgs[cen:-1:1], lk_params; mask) + for (i,tr) in enumerate(tracks) + img_tracks[-i] = [tr[k,:,:][:] for k in 1:size(tr,1)] + end + + return img_tracks, dscs0 +end + + +function makeBlobFeatureTracksPerImage_FwdBck!( + dfg::AbstractDFG, + vlbs_fwdbck::AbstractVector{Symbol}, + imgBlobKey, + blobstorelbl::Symbol, + blobLabel::Symbol = Symbol("IMG_FEATURE_TRACKS_FWDBCK_$(length(vlbs_fwdbck))_KLT"), + descLabel::Symbol = Symbol("IMG_FEATURE_ANG_ORB"); + feature_params, + lk_params, + mask, + orb = cv.ORB_create() +) + # good features to track + kfs = (s->getData(dfg, s, imgBlobKey)).(vlbs_fwdbck) + imgs = kfs .|> (eb)->unpackBlob(MIME(eb[1].mimeType), eb[2]) + # track features across neighboring frames +-1, +-2, ... + img_tracks, dscs0 = trackFeaturesForwardsBackwards(imgs, feature_params, lk_params; mask, orb) + + center_vlb = vlbs_fwdbck[1+floor(Int,length(vlbs_fwdbck)/2)] + + # store feature keypoints and tracks + Caesar.addDataImgTracksFwdBck!( + dfg, + center_vlb, + blobstorelbl, + blobLabel, + "", + img_tracks, + ) + + # only store descriptors if available + if 0 < length(dscs0) + # store feature angles and descriptors in a separate blob + blob = Vector{UInt8}(JSON3.write(dscs0)) + entry = BlobEntry(; + label = descLabel, + blobstore = blobstorelbl, + hash = bytes2hex(sha256(blob)), + origin = "", + size = length(blob), + description = "Image feature angles and ORB descriptors from cv2.py", + mimeType = "application/octet-stream/json; _type=JuliaLang.$(typeof(dscs0))" + ) + addData!(dfg, center_vlb, entry, blob) + end +end + +function makeORBParams( + feature_params; + nfeatures = feature_params.maxCorners, + nlevels = 1, + fastThreshold = 20, + edgeThreshold = 31, + firstLevel = 0, + patchSize = 31, + WTA_K = 2, + scaleFactor = 1.1, + scoreType = 1, +) + + orb = cv.ORB_create( + nlevels = nlevels, + fastThreshold = fastThreshold, + edgeThreshold = edgeThreshold, + firstLevel = firstLevel, + patchSize = patchSize, + WTA_K = WTA_K, + nfeatures = nfeatures, + scaleFactor = scaleFactor, + scoreType = scoreType, + ) + # orb.setMaxFeatures(feature_params.maxCorners) + # orb.setPatchSize(feature_params.blockSize) + # orb.setNLevels(1) + # orb.setScoreType(1) # FAST + return orb +end + + +# visualization aid + +function plotBlobsImageTracks!( + dfg::AbstractDFG, + vlb::Symbol, + key = r"IMG_FEATURE_TRACKS_FWDBCK"; + fig = GLMakie.Figure(), + ax = GLMakie.Axis(fig[1,1]), + resolution::Union{Nothing,<:Tuple} = nothing, + img::Union{Nothing,<:AbstractMatrix{<:Colorant}} = nothing, + linewidth = 5 +) + + height = 0 + if !isnothing(img) + image!(ax, rotr90(img)) + height = size(img,1) + end + + eb = getData(dfg,vlb,key) + img_tracks = JSON3.read(String(eb[2]), Dict{Int, Vector{Vector{Float32}}}) + + len = length(img_tracks) + UU = [Vector{Float64}() for k in 1:len] + VV = [Vector{Float64}() for k in 1:len] + + fbk = floor(Int, (len-1)/2) + for k in 1:len + for i in -fbk:fbk + push!(UU[k], img_tracks[i][k][1]) + push!(VV[k], height-img_tracks[i][k][2]) + end + lines!(ax, UU[k], VV[k]; color=RGBf(rand(3)...), linewidth) + end + if !isnothing(resolution) + xlims!(ax, 0, resolution[1]) + ylims!(ax, height - resolution[2], height) + # ylims!(ax, -resolution[2], 0) + end + + fig +end + + diff --git a/ext/services/WeakdepsPrototypes.jl b/ext/services/WeakdepsPrototypes.jl index bb14ebb..aa343da 100644 --- a/ext/services/WeakdepsPrototypes.jl +++ b/ext/services/WeakdepsPrototypes.jl @@ -1,5 +1,21 @@ # prototypes for functions in this PyCaesar extensions + +function whatcv end + +# Images.jl +function calcFlow end +function getPose end +function goodFeaturesToTrack end +function goodFeaturesToTrackORB end +function combinePlot end +function trackFeaturesFrames end +function trackFeaturesForwardsBackwards end +function makeBlobFeatureTracksPerImage_FwdBck! end +function makeORBParams end +function plotBlobsImageTracks! end + +# RobotOS.jl function loop! end function getROSPyMsgTimestamp end function nanosecond2datetime end \ No newline at end of file diff --git a/pyproject.toml b/pyproject.toml new file mode 100644 index 0000000..37fd7c0 --- /dev/null +++ b/pyproject.toml @@ -0,0 +1,7 @@ +[project] +name = "PyCaesar" +version = "0.1.0" +# ... +dependencies = [ + "opencv-python >= 4.8", +] \ No newline at end of file diff --git a/test/runtests.jl b/test/runtests.jl index fc690d8..aca21aa 100644 --- a/test/runtests.jl +++ b/test/runtests.jl @@ -4,8 +4,20 @@ using PyCaesar ## -PyCaesar.version() +@test PyCaesar.version() isa VersionNumber ## +using Images +using TestImages + +## + +img = testimage("cameraman") # without extension works + +kps, dsc = PyCaesar.goodFeaturesToTrackORB(img) + +@test 1 < length(kps) +@test dsc isa Matrix + # using RobotOS \ No newline at end of file