diff --git a/Project.toml b/Project.toml index e080a07..4b7aa99 100644 --- a/Project.toml +++ b/Project.toml @@ -1,11 +1,12 @@ name = "CameraModels" uuid = "0d57b887-6120-40e6-8b8c-29d3116bc0c1" -keywords = ["camera", "model", "pinhole", "distortion", "robotics", "images"] +keywords = ["camera", "model", "pinhole", "distortion", "robotics", "images", "vision"] version = "0.2.4" [deps] DocStringExtensions = "ffbed154-4ef7-542d-bbb7-c09d3a79fcae" LinearAlgebra = "37e2e46d-f89d-539d-b4ee-838fcccc9c8e" +LoopVectorization = "bdcacae8-1622-11e9-2a5c-532679323890" Manifolds = "1cead3c2-87b3-11e9-0ccd-23c62b72b94e" RecursiveArrayTools = "731186ca-8d62-57ce-b412-fbd966d074cd" Rotations = "6038ab10-8711-5258-84ad-4b1120ba62dc" @@ -13,6 +14,7 @@ StaticArrays = "90137ffa-7385-5640-81b9-e52037218182" [compat] DocStringExtensions = "0.8, 0.9" +LoopVectorization = "0.12.173" Manifolds = "0.10, 0.11" RecursiveArrayTools = "3.27.0" Rotations = "1" diff --git a/src/CameraModels.jl b/src/CameraModels.jl index 4982a8b..cd2625f 100644 --- a/src/CameraModels.jl +++ b/src/CameraModels.jl @@ -7,6 +7,7 @@ using StaticArrays import Rotations as Rot_ import Base: getindex, getproperty, show using RecursiveArrayTools: ArrayPartition +using LoopVectorization: @tturbo # exports include("ExportAPI.jl") @@ -26,6 +27,4 @@ include("services/CameraServices.jl") include("services/Utils.jl") - - end # module diff --git a/src/Deprecated.jl b/src/Deprecated.jl index ffc3d51..2d0e49e 100644 --- a/src/Deprecated.jl +++ b/src/Deprecated.jl @@ -1,12 +1,11 @@ - ## ================================================================================================ ## consolidated types from various repos in Julia ecosystem ## ================================================================================================ -@deprecate project(cm::CameraModelFull, pt::AbstractVector{<:Real}) project(cm.ci,pt) # drops extrinsics +@deprecate project(cm::CameraModelFull, pt::AbstractVector{<:Real}) project(cm.ci, pt) # drops extrinsics # function project( -# cm::CameraModelFull, +# cm::CameraModelFull, # pt::AbstractVector{<:Real} # ) # res = Vector{Float64}(2) @@ -21,7 +20,7 @@ A Union type for users to implement against both `struct`` and `mutable struct` """ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable} -@deprecate CameraExtrinsic(R::AbstractMatrix=[1 0 0; 0 1 0; 0 0 1.], t::AbstractVector=[0,0,0.]) ArrayPartition(SVector(t...),SMatrix(R)) +@deprecate CameraExtrinsic(R::AbstractMatrix = [1 0 0; 0 1 0; 0 0 1.0], t::AbstractVector = [0, 0, 0.0]) ArrayPartition(SVector(t...), SMatrix(R)) # Camera extrinsic must be world in camera frame (cRw) # Base.@kwdef struct CameraExtrinsic{T <: Real} @@ -30,7 +29,7 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable} # end -@deprecate PixelCoordinate(row,col) PixelIndex(row,col) +@deprecate PixelCoordinate(row, col) PixelIndex(row, col) # CameraCalibration( # height::Int= 480, @@ -52,7 +51,6 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable} # ) = CameraCalibrationMutable(height, width, kc, MMatrix{3,3}(K), MMatrix{3,3}(inv(K)) ) - @deprecate point2pixel(model, pt) project(model, pt[[1;3;2]]) @deprecate pixel2ray(model, px) backproject(model, px)[[1;3;2]] @@ -61,7 +59,7 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable} # point2pixel(model::Pinhole, pointincamera::$(Point3)) # Return a transformation that converts real-world coordinates -# to camera coordinates. This currently ignores any tangential +# to camera coordinates. This currently ignores any tangential # distortion between the lens and the image plane. # """ # function point2pixel(model::CameraCalibrationT, pointincamera::Point3) @@ -75,7 +73,7 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable} # pixel2ray(model::Pinhole, pixelcoordinate::$(PixelCoordinate)) # Return a transformation that converts real-world coordinates -# to camera coordinates. This currently ignores any tangential +# to camera coordinates. This currently ignores any tangential # distortion between the lens and the image plane. # """ # function pixel2ray(model::CameraCalibrationT, pixelcoordinate::PixelCoordinate) @@ -86,19 +84,19 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable} export CameraModel # being replaced by AbstractCameraModel -CameraModel = (@warn("CameraModels.CameraModel is deprecated, use CameraModels.AbstractCameraModel instead");AbstractCameraModel) -# abstract type CameraModel end +CameraModel = (@warn("CameraModels.CameraModel is deprecated, use CameraModels.AbstractCameraModel instead"); AbstractCameraModel) +# abstract type CameraModel end @warn "RadialDistortion is deprecated, use CameraCalibration instead" # Base.@kwdef struct RadialDistortion{N, R <: Real, K <: AbstractVector} -# Ki::SVector{N,R} = SVector(0.0) # +# Ki::SVector{N,R} = SVector(0.0) # # center::SVector{2,R} = SVector{2,R}(0.0,0.0) # SVector{2,R} # [h,w] # # _radius2::Matrix{R} # perhaps SizedArray{R,2} or StaticArray{R,2} or GPUArray{R,2} depending on performance # end -@deprecate columns(w...;kw...) width(w...;kw...) -@deprecate rows(w...;kw...) height(w...;kw...) +@deprecate columns(w...; kw...) width(w...; kw...) +@deprecate rows(w...; kw...) height(w...; kw...) # sensorsize(cameramodel::CameraModel) = SVector{2}(width(cameramodel), height(cameramodel)) @@ -107,22 +105,21 @@ export CameraModelandParameters # const CameraModelandParameters = (@warn("CameraModels.CameraModelandParameters is deprecated, use CameraModels.CameraCalibration instead.");CameraCalibration) function CameraModelandParameters( - width::Int, - height::Int, - fc::AbstractVector{<:Real}, - cc::AbstractVector{<:Real}, - skew::Real, - kc::AbstractVector{<:Real}, - K::AbstractMatrix{<:Real} = [[fc[1];skew;cc[1]]';[0.0;fc[2];cc[2]]';[0.0;0;1]'], # legacy constructor - Ki::AbstractMatrix{<:Real} = inv(K) - ) - # - @warn("CameraModels.CameraModelandParameters is deprecated, use CameraModels.CameraCalibration instead.") - CameraCalibration(;width,height,K=SMatrix{3,3}(K)) + width::Int, + height::Int, + fc::AbstractVector{<:Real}, + cc::AbstractVector{<:Real}, + skew::Real, + kc::AbstractVector{<:Real}, + K::AbstractMatrix{<:Real} = [[fc[1];skew;cc[1]]';[0.0;fc[2];cc[2]]';[0.0;0;1]'], # legacy constructor + Ki::AbstractMatrix{<:Real} = inv(K) + ) + # + @warn("CameraModels.CameraModelandParameters is deprecated, use CameraModels.CameraCalibration instead.") + return CameraCalibration(; width, height, K = SMatrix{3, 3}(K)) end - # """ # Data structure for a Camera model with parameters. # Use `CameraModel(width,height,fc,cc,skew,kc)` for easy construction. @@ -139,7 +136,6 @@ end # end - export PinholeCamera # ## From JuliaRobotics/Caesar.jl @@ -152,7 +148,7 @@ export PinholeCamera # - https://en.wikipedia.org/wiki/Pinhole_camera # - Standard Julia *[Images.jl](https://juliaimages.org/latest/)-frame* convention is, `size(img) <==> (i,j) <==> (height,width) <==> (y,x)`, # - Common *camera-frame* in computer vision and robotics, `(x,y) <==> (width,height) <==> (j,i)`, -# - Using top left corner of image as `(0,0)` in all cases. +# - Using top left corner of image as `(0,0)` in all cases. # - Direct comparison with [OpenCV convention](https://docs.opencv.org/3.4/d9/d0c/group__calib3d.html) is: # - `(x,y) [CamXYZ] <==> (j,i) [Images.jl] <==> (u,v) [OpenCV]` -- look very carfully at `(u,v) <==> (j,i)` in *image-frame* # - Always follow right hand rule for everything. @@ -168,23 +164,23 @@ export PinholeCamera # const PinholeCamera = (@warn("CameraModels.PinholeCamera is deprecated, use CameraModels.CameraCalibrationMutable instead."); CameraCalibration) function PinholeCamera( - K_::AbstractMatrix=[[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor - width::Int=round(Int, K_[1,3]*2), - height::Int=round(Int, K_[2,3]*2), - f_w::Real=K_[1,1], - f_h::Real=K_[2,2], - c_w::Real=K_[1,3], - c_h::Real=K_[2,3], - shear::Real=K_[1,2], - K::AbstractMatrix=[[f_w;shear;c_w]';[0.0;f_h;c_h]';[0.0;0;1]'], # consolidated matrix K -) - # - @warn "CameraModels.PinholeCamera is deprecated, use CameraModels.CameraCalibrationMutable instead." - if 3 < size(K_,1) - @warn "PinholeCamera(arg), 3 < size(arg,1), assuming legacy constructor as img as input argument." - return CameraCalibrationMutable(K_) # as though img=K_ - end - CameraCalibrationMutable(;width,height,K=MMatrix{3,3}(K)) + K_::AbstractMatrix = [[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor + width::Int = round(Int, K_[1, 3] * 2), + height::Int = round(Int, K_[2, 3] * 2), + f_w::Real = K_[1, 1], + f_h::Real = K_[2, 2], + c_w::Real = K_[1, 3], + c_h::Real = K_[2, 3], + shear::Real = K_[1, 2], + K::AbstractMatrix = [[f_w;shear;c_w]';[0.0;f_h;c_h]';[0.0;0;1]'], # consolidated matrix K + ) + # + @warn "CameraModels.PinholeCamera is deprecated, use CameraModels.CameraCalibrationMutable instead." + if 3 < size(K_, 1) + @warn "PinholeCamera(arg), 3 < size(arg,1), assuming legacy constructor as img as input argument." + return CameraCalibrationMutable(K_) # as though img=K_ + end + return CameraCalibrationMutable(; width, height, K = MMatrix{3, 3}(K)) end # @deprecate PinholeCamera(img::AbstractMatrix) CameraCalibrationMutable(img) @@ -216,28 +212,28 @@ export Pinhole ## From yakir12/CameraModels.jl # const Pinhole = (@warn("CameraModels.Pinhole is deprecated, use CameraModels.CameraCalibration instead."); CameraCalibration) -function Pinhole(columns::Int,rows::Int,prinicipalpoint,focallength::Vector2 ) - @warn "CameraModels.Pinhole is deprecated, use CameraModels.CameraCalibration instead." - f_w,f_h = focallength[1], focallength[2] - c_w,c_h = prinicipalpoint[1], prinicipalpoint[2] - K = SMatrix{3,3}([[f_w;0.0;c_w]';[0.0;f_h;c_h]';[0.0;0;1.]'] ) - CameraCalibration(; - height=rows, - width=columns, - K - ) +function Pinhole(columns::Int, rows::Int, prinicipalpoint, focallength::Vector2) + @warn "CameraModels.Pinhole is deprecated, use CameraModels.CameraCalibration instead." + f_w, f_h = focallength[1], focallength[2] + c_w, c_h = prinicipalpoint[1], prinicipalpoint[2] + K = SMatrix{3, 3}([[f_w;0.0;c_w]';[0.0;f_h;c_h]';[0.0;0;1.0]']) + return CameraCalibration(; + height = rows, + width = columns, + K + ) end function CameraIntrinsic( - K_::AbstractMatrix=[[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor - x0=320.0,y0=240.0,fx=510.0,fy=510.0,s=0.0, # legacy function support - K::AbstractMatrix=[[fx;s;x0]';[0.0;fy;y0]';[0.0;0;1]'], # consolidated matrix K - width::Int=round(Int, K[1,3]*2), - height::Int=round(Int, K[2,3]*2), -) - # - @warn "CameraModels.CameraIntrinsic is deprecated, use CameraModels.CameraCalibration instead." - CameraCalibration(;width,height,K) + K_::AbstractMatrix = [[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor + x0 = 320.0, y0 = 240.0, fx = 510.0, fy = 510.0, s = 0.0, # legacy function support + K::AbstractMatrix = [[fx;s;x0]';[0.0;fy;y0]';[0.0;0;1]'], # consolidated matrix K + width::Int = round(Int, K[1, 3] * 2), + height::Int = round(Int, K[2, 3] * 2), + ) + # + @warn "CameraModels.CameraIntrinsic is deprecated, use CameraModels.CameraCalibration instead." + return CameraCalibration(; width, height, K) end export CameraIntrinsic @@ -251,23 +247,23 @@ export CameraIntrinsic function Base.getproperty( - x::CameraCalibration, # Union{<:Pinhole, CameraModelandParameters}, - f::Symbol, -) - if f == :skew - getfield(x, :K)[1,2] - elseif f == :columns - getfield(x, :width) - elseif f == :rows - getfield(x, :height) - elseif f == :prinicipalpoint || f == :cc - SA[(getfield(x, :K)[1:2, 3])...] - elseif f == :focallength || f == :fc - K = getfield(x, :K) - SA[K[1,1];K[2,2]] - else - getfield(x, f) - end + x::CameraCalibration, # Union{<:Pinhole, CameraModelandParameters}, + f::Symbol, + ) + return if f == :skew + getfield(x, :K)[1, 2] + elseif f == :columns + getfield(x, :width) + elseif f == :rows + getfield(x, :height) + elseif f == :prinicipalpoint || f == :cc + SA[(getfield(x, :K)[1:2, 3])...] + elseif f == :focallength || f == :fc + K = getfield(x, :K) + SA[K[1, 1];K[2, 2]] + else + getfield(x, f) + end end # function Base.getproperty(x::CameraModelandParameters, f::Symbol) # if f == :skew @@ -280,7 +276,7 @@ end # SA[(getfield(x, :K)[1:2, 3])...] # elseif f == :focallength || f == :fc # K = getfield(x, :K) -# SA[K[1,1];K[2,2]] +# SA[K[1,1];K[2,2]] # else # getfield(x, f) # end @@ -296,7 +292,4 @@ end # end - - - -# \ No newline at end of file +# diff --git a/src/ExportAPI.jl b/src/ExportAPI.jl index bd31a09..bac4692 100644 --- a/src/ExportAPI.jl +++ b/src/ExportAPI.jl @@ -1,6 +1,3 @@ - - - export AbstractCameraModel export CameraCalibration, CameraCalibrationMutable @@ -10,7 +7,7 @@ export CameraSkewDistortion export undistortPoint export Ray, PixelIndex -export pixel2ray, point2pixel, canreproject, sensorsize #, origin, direction, +export pixel2ray, point2pixel, canreproject, sensorsize #, origin, direction, export project, projectHomogeneous export backproject, backprojectHomogeneous export pp_w, pp_h, f_w, f_h @@ -21,4 +18,4 @@ export intersectLineToPlane3D, intersectRayToPlane # suppressing super general signatures likely to have conflicts. # TODO adopt common Julia definition for points and vectors, maybe something from JuliaGeometry, etc. -# export Vector3, Vector2, Point3 \ No newline at end of file +# export Vector3, Vector2, Point3 diff --git a/src/entities/CameraCalibration.jl b/src/entities/CameraCalibration.jl index dd22c5d..daf4d56 100644 --- a/src/entities/CameraCalibration.jl +++ b/src/entities/CameraCalibration.jl @@ -1,4 +1,3 @@ - """ $TYPEDEF @@ -23,7 +22,7 @@ Notes - Common *camera-frame* in computer vision and robotics, `(x,y) <==> (width,height) <==> (j,i)`, - Using top left corner of image as `(0,0)` in all cases. - Direct comparison with [OpenCV convention](https://docs.opencv.org/3.4/d9/d0c/group__calib3d.html) is: - - `(x,y) [CamXYZ] <==> (j,i) [Images.jl] <==> (u,v) [OpenCV]` -- look very carfully at `(u,v) <==> (j,i)` in *image-frame* + - `(x,y) [CamXYZ] <==> (j,i) [Images.jl] <==> (u,v) [OpenCV]` -- look very carefully at `(u,v) <==> (j,i)` in *image-frame* - Always follow right hand rule for everything. - An abstract type [`AbstractCameraModel`](@ref) is provided to develop implementations against `struct` and `mutable struct` types. @@ -33,53 +32,48 @@ DevNotes Also see: [`AbstractCameraModel`](@ref) [`CameraCalibrationMutable`](@ref), (TODO: `ProjectiveCameraModel`) """ -Base.@kwdef struct CameraCalibration{R <: Real,N} <: AbstractCameraModel - """ number of pixels from top to bottom """ - height::Int = 480 - """ number of pixels from left to right """ - width::Int = 640 - """ distortion coefficients up to fifth order """ - kc::SVector{N,R} = SVector(zeros(5)...) - """ 3x3 camera calibration matrix """ - K::SMatrix{3,3,R,9} = SMatrix{3,3}([[1.1*height;0.0;width/2]';[0.0;1.1*height;height/2]';[0.0;0;1.]'] ) - """ inverse of a 3x3 camera calibration matrix """ - Ki::SMatrix{3,3,R,9} = inv(K) +Base.@kwdef struct CameraCalibration{R <: Real, N} <: AbstractCameraModel + """ number of pixels from top to bottom """ + height::Int = 480 + """ number of pixels from left to right """ + width::Int = 640 + """ distortion coefficients up to fifth order """ + kc::SVector{N, R} = SVector(zeros(5)...) + """ 3x3 camera calibration matrix """ + K::SMatrix{3, 3, R, 9} = SMatrix{3, 3}([[1.1 * height;0.0;width / 2]';[0.0;1.1 * height;height / 2]';[0.0;0;1.0]']) + """ inverse of a 3x3 camera calibration matrix """ + Ki::SMatrix{3, 3, R, 9} = inv(K) end """ $TYPEDEF -See [`CameraCalibraton`](@ref). +See [`CameraCalibration`](@ref). """ -Base.@kwdef mutable struct CameraCalibrationMutable{R <: Real,N} <: AbstractCameraModel - """ number of pixels from top to bottom """ - height::Int = 480 - """ number of pixels from left to right """ - width::Int = 640 - """ distortion coefficients up to fifth order """ - kc::MVector{N,R} = MVector(zeros(5)...) - """ 3x3 camera calibration matrix """ - K::MMatrix{3,3,R} = MMatrix{3,3}([[1.1*height;0.0;width/2]';[0.0;1.1*height;height/2]';[0.0;0;1.]'] ) - """ inverse of a 3x3 camera calibration matrix """ - Ki::MMatrix{3,3,R} = inv(K) +Base.@kwdef mutable struct CameraCalibrationMutable{R <: Real, N} <: AbstractCameraModel + """ number of pixels from top to bottom """ + height::Int = 480 + """ number of pixels from left to right """ + width::Int = 640 + """ distortion coefficients up to fifth order """ + kc::MVector{N, R} = MVector(zeros(5)...) + """ 3x3 camera calibration matrix """ + K::MMatrix{3, 3, R} = MMatrix{3, 3}([[1.1 * height;0.0;width / 2]';[0.0;1.1 * height;height / 2]';[0.0;0;1.0]']) + """ inverse of a 3x3 camera calibration matrix """ + Ki::MMatrix{3, 3, R} = inv(K) end - - - ## =========================================================================== ## Legacy types that are not so easy to consolidate (not exported) DO NOT USE ## =========================================================================== Base.@kwdef struct CameraModelFull - ci::CameraCalibration = CameraCalibration() - ce::ArrayPartition = ArrayPartition(SVector(0.,0.,0.),SMatrix{3,3}(1.,0.,0.,0.,1.,0.,0.,0.,1.)) # CameraExtrinsic() + ci::CameraCalibration = CameraCalibration() + ce::ArrayPartition = ArrayPartition(SVector(0.0, 0.0, 0.0), SMatrix{3, 3}(1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0)) # CameraExtrinsic() end - - -# \ No newline at end of file +# diff --git a/src/entities/GeneralTypes.jl b/src/entities/GeneralTypes.jl index 2b6af02..55a652b 100644 --- a/src/entities/GeneralTypes.jl +++ b/src/entities/GeneralTypes.jl @@ -1,23 +1,15 @@ - - struct PixelIndex{VALID, T <: Real} row::T col::T depth::T end -PixelIndex(u::T, v::T; valid::Bool=true, depth = T(0)) where {T <: Real} = PixelIndex{valid,T}(u, v, depth) +PixelIndex(u::T, v::T; valid::Bool = true, depth = T(0)) where {T <: Real} = PixelIndex{valid, T}(u, v, depth) -function Base.getindex(p::PixelIndex,i::Int) - if i === 1 - p.row - elseif i === 2 - p.col - elseif i === 3 - p.depth - else - DomainError("Camera only has rows and columns, cannot index to $i") - end -end +Base.getindex(p::PixelIndex, i::Int) = + i == 1 ? p.row : + i == 2 ? p.col : + i == 3 ? p.depth : + throw(DomainError(i, "Camera only has rows, columns and depth")) const Vector2 = SVector{2, Float64} @@ -32,4 +24,4 @@ origin3d = zeros(Point3) struct Ray origin::Point3 direction::Vector3 -end \ No newline at end of file +end diff --git a/src/services/CameraCalibration.jl b/src/services/CameraCalibration.jl index f79aa74..c286f95 100644 --- a/src/services/CameraCalibration.jl +++ b/src/services/CameraCalibration.jl @@ -1,20 +1,18 @@ - function Base.show(io::IO, ::MIME"text/plain", cam::CameraCalibration) - println(io,"CameraCalibration {") - println(io," sensorsize (w,h) = ", sensorsize(cam)) - println(io," principal_point (w,h) = ", pp_w(cam), ",", pp_h(cam)) - println(io," focal_length (w,h) = ", f_w(cam), ",", f_h(cam)) - println(io," shear = ", shear(cam)) - println(io," radtan coeff = ", cam.kc) - println(io, "}") - nothing + println(io, "CameraCalibration {") + println(io, " sensorsize (w,h) = ", sensorsize(cam)) + println(io, " principal_point (w,h) = ", pp_w(cam), ",", pp_h(cam)) + println(io, " focal_length (w,h) = ", f_w(cam), ",", f_h(cam)) + println(io, " shear = ", shear(cam)) + println(io, " radtan coeff = ", cam.kc) + println(io, "}") + return nothing end Base.show(io::IO, ::MIME"text/markdown", cam::CameraCalibration) = show(io, MIME("text/plain"), cam) Base.show(io::IO, cam::CameraCalibration) = show(io, MIME("text/plain"), cam) - """ $SIGNATURES @@ -24,14 +22,13 @@ Notes: - Calibration will incorrect but hopefully in a distant ballpark to get the calibration process started. - See [AprilTags.jl Calibration section](https://juliarobotics.org/AprilTags.jl/latest/#Camera-Calibration-1) for code and help. """ -function CameraCalibrationMutable(img::AbstractMatrix{T}) where T - height, width = size(img) - # emperical assumption usually seen for focal length - f_w = 1.1*height - f_h = f_w - c_w, c_h = width/2, height/2 - K = MMatrix{3,3}([[f_w;0.0;c_w]';[0.0;f_h;c_h]';[0.0;0;1.]'] ) - @info "Assuming default CameraCalibrationMutable from image size(img)=(rows,cols)=$(size(img)):" f_w f_h c_w c_h - CameraCalibrationMutable(;width, height, K) +function CameraCalibrationMutable(img::AbstractMatrix{T}) where {T} + height, width = size(img) + # emperical assumption usually seen for focal length + f_w = 1.1 * height + f_h = f_w + c_w, c_h = width / 2, height / 2 + K = MMatrix{3, 3}([[f_w;0.0;c_w]';[0.0;f_h;c_h]';[0.0;0;1.0]']) + @info "Assuming default CameraCalibrationMutable from image size(img)=(rows,cols)=$(size(img)):" f_w f_h c_w c_h + return CameraCalibrationMutable(; width, height, K) end - diff --git a/src/services/CameraServices.jl b/src/services/CameraServices.jl index b03eaac..7d014c2 100644 --- a/src/services/CameraServices.jl +++ b/src/services/CameraServices.jl @@ -1,32 +1,31 @@ - ## consolidated functions, first baseline ## ========================================================================================= ## Parameter functions ## From yakir12/CameraModels.jl -origin(vector::Union{<:AbstractVector{<:Real},<:Vector3}) = origin3d +origin(vector::Union{<:AbstractVector{<:Real}, <:Vector3}) = origin3d origin(ray::Ray) = ray.origin -lookdirection(cameramodel::AbstractCameraModel) = SVector{3}(0,1,0) -updirection(cameramodel::AbstractCameraModel) = SVector{3}(0,0,1) +lookdirection(cameramodel::AbstractCameraModel) = SVector{3}(0, 1, 0) +updirection(cameramodel::AbstractCameraModel) = SVector{3}(0, 0, 1) width(cameramodel::AbstractCameraModel) = cameramodel.width -height(cameramodel::AbstractCameraModel) = cameramodel.height -direction(vector::Union{<:AbstractVector{<:Real},<:Vector3}) = vector +height(cameramodel::AbstractCameraModel) = cameramodel.height +direction(vector::Union{<:AbstractVector{<:Real}, <:Vector3}) = vector direction(ray::Ray) = ray.direction sensorsize(cameramodel::AbstractCameraModel) = SVector{2}(width(cameramodel), height(cameramodel)) ## From JuliaRobotics/Caesar.jl -f_w(pc::AbstractCameraModel) = pc.K[1,1] -f_h(pc::AbstractCameraModel) = pc.K[2,2] -shear(pc::AbstractCameraModel) = pc.K[1,2] -pp_w(pc::AbstractCameraModel) = pc.K[1,3] -pp_h(pc::AbstractCameraModel) = pc.K[2,3] - -set_f_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,1] = val) -set_f_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,2] = val) -set_shear!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,2] = val) -set_pp_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,3] = val) -set_pp_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,3] = val) +f_w(pc::AbstractCameraModel) = pc.K[1, 1] +f_h(pc::AbstractCameraModel) = pc.K[2, 2] +shear(pc::AbstractCameraModel) = pc.K[1, 2] +pp_w(pc::AbstractCameraModel) = pc.K[1, 3] +pp_h(pc::AbstractCameraModel) = pc.K[2, 3] + +set_f_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1, 1] = val) +set_f_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2, 2] = val) +set_shear!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1, 2] = val) +set_pp_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1, 3] = val) +set_pp_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2, 3] = val) """ canreproject(camera::CameraModel) @@ -44,24 +43,24 @@ canreproject(camera::AbstractCameraModel) = true ## ========================================================================================= -function undistortPoint(cam::CameraCalibration, xy, iter_num=3) - k1, k2, p1, p2, k3 = cam.kc[1:5] - fx, fy = f_w(cam), f_h(cam) # cam.K[1, 1], cam.K[2, 2] - cx, cy = pp_w(cam), pp_h(cam) # cam.K[1:2, 3] - x, y = xy[1], xy[2] - x = (x - cx) / fx - x0 = x - y = (y - cy) / fy - y0 = y - for _ in 1:iter_num - r2 = x^2 + y^2 - k_inv = 1 / (1 + k1*r2 + k2*r2^2 + k3*r2^3) - delta_x = 2*p1*x*y + p2 * (r2 + 2*x^2) - delta_y = p1*(r2 + 2*y^2) + 2*p2*x*y - x = (x0 - delta_x) * k_inv - y = (y0 - delta_y) * k_inv - end - return SA[x*fx+cx; y*fy+cy] +function undistortPoint(cam::CameraCalibration, xy, iter_num = 3) + k1, k2, p1, p2, k3 = cam.kc[1:5] + fx, fy = f_w(cam), f_h(cam) # cam.K[1, 1], cam.K[2, 2] + cx, cy = pp_w(cam), pp_h(cam) # cam.K[1:2, 3] + x, y = xy[1], xy[2] + x = (x - cx) / fx + x0 = x + y = (y - cy) / fy + y0 = y + for _ in 1:iter_num + r2 = x^2 + y^2 + k_inv = 1 / (1 + k1 * r2 + k2 * r2^2 + k3 * r2^3) + delta_x = 2 * p1 * x * y + p2 * (r2 + 2 * x^2) + delta_y = p1 * (r2 + 2 * y^2) + 2 * p2 * x * y + x = (x0 - delta_x) * k_inv + y = (y0 - delta_y) * k_inv + end + return SA[x * fx + cx; y * fy + cy] end @@ -72,14 +71,14 @@ end ## From JuliaRobotics/SensorFeatureTracking.jl function project!( - ret::AbstractVector{<:Real}, - ci::CameraCalibration, #CameraIntrinsic, - c_T_r::ArrayPartition, - r_P::AbstractVector{<:Real} -) - res = ci.K*(c_T_r.x[2]*r_P + c_T_r.x[1]) - ret[1:2] ./= res[3] - PixelIndex(ret[1], ret[2]) + ret::AbstractVector{<:Real}, + ci::CameraCalibration, #CameraIntrinsic, + c_T_r::ArrayPartition, + r_P::AbstractVector{<:Real} + ) + res = ci.K * (c_T_r.x[2] * r_P + c_T_r.x[1]) + ret[1:2] ./= res[3] + return PixelIndex(ret[1], ret[2]) end """ @@ -101,45 +100,45 @@ Deprecates: Also see: [`backproject`](@ref) """ function project( - model::AbstractCameraModel, - r_P::Union{<:AbstractVector{<:Real}, <:Point3}; - c_T_r = ArrayPartition( SVector(0.,0.,0.), SMatrix{3,3}(1.,0.,0.,0.,1.,0.,0.,0.,1.) ) - ) - # - ret = MVector(0.,0.) - project!(ret, model, c_T_r, r_P) - # column = pp_w(model) + f_w(model) * c_P[1] / c_P[3] - # row = pp_h(model) - f_h(model) * c_P[2] / c_P[3] - # return PixelIndex(column, row) + model::AbstractCameraModel, + r_P::Union{<:AbstractVector{<:Real}, <:Point3}; + c_T_r = ArrayPartition(SVector(0.0, 0.0, 0.0), SMatrix{3, 3}(1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0)) + ) + # + ret = MVector(0.0, 0.0) + return project!(ret, model, c_T_r, r_P) + # column = pp_w(model) + f_w(model) * c_P[1] / c_P[3] + # row = pp_h(model) - f_h(model) * c_P[2] / c_P[3] + # return PixelIndex(column, row) end project!( - ret::AbstractVector{<:Real}, - cm::CameraModelFull, - pt::AbstractVector{<:Real}) = project!(ret, cm.ci, cm.ce, pt) + ret::AbstractVector{<:Real}, + cm::CameraModelFull, + pt::AbstractVector{<:Real} +) = project!(ret, cm.ci, cm.ce, pt) ## homogeneous point coords xyzw (stereo cameras) # xyzw are in the camera frame (c_), i.e. x-columns, y-rows, z-forward function projectHomogeneous( - cam::AbstractCameraModel, - c_Ph::AbstractVector, -) - # left cam - x,y,z,w = (c_Ph...,) - fx_z = f_w(cam) / z - fy_z = f_h(cam) / z - col = x * fx_z + pp_w(cam) # add center to get PixelIndex - row = y * fy_z + pp_h(cam) - # infront or behind - depth=z/w - PixelIndex(row, col; depth, valid = (w==0&&0 either via dispatch with AMDGPU and CUDA (should be avoided) + -> or using a vendor-agnostic code with KernelAbstractions.jl """ function radialDistortion!( - cc::CameraCalibration{<:Real,N}, - dest::AbstractMatrix, - src::AbstractMatrix -) where N - # loop over entire image - for h_d in size(src,1), w_d in size(src,2) - # temporary coordinates - @inbounds h_ = h_d - cc.center[1] - @inbounds w_ = w_d - cc.center[2] - # calculate the radius from distortion center - _radius2 = h_^2 + w_^2 - # calculate the denominator - _denomin = 1 - @inbounds @fastmath for k in 1:N - _denomin += cc.kc[k]*(_radius2^k) + cc::CameraCalibration{<:Real, N}, + dest::AbstractMatrix, + src::AbstractMatrix + ) where {N} + + center = SVector{2}(cc.center) + k = ntuple(i -> cc.kc[i], N) + H, W = size(src) + c₁, c₂ = center + + # pre-allocate buffers for the radius powers + buf = Vector{T}(undef, max(H, W)) + + @tturbo for h_d in 1:H, w_d in 1:W + h_ = h_d - c₁ + w_ = w_d - c₂ + r² = h_ * h_ + w_ * w_ + + num = one(T) + rⁿ = r² + for i in 1:N + num += k[i] * rⁿ + rⁿ *= r² end - # calculate the new 'undistorted' coordinates and set equal to incoming image - @inbounds @fastmath h_u = cc.center[1] + h_/_denomin - @inbounds @fastmath w_u = cc.center[2] + h_/_denomin - dest[h_u,w_u] = src[h_d,w_d] + + h_u = c₁ + h_ / num + w_u = c₂ + w_ / num + + # nearest-neighbour lookup (round + clamp) + hi = clamp(round(Int, h_u), 1, H) + wi = clamp(round(Int, w_u), 1, W) + dest[h_d, w_d] = src[hi, wi] end - nothing + return nothing end +""" + intersectLineToPlane3D(planenorm, planepnt, raydir, raypnt) -> point + +Compute the unique intersection point between an infinite 3-D line (ray) and a plane. + +# Arguments +- `planenorm::AbstractVector{<:Real}` – plane normal vector (need not be unit-length) +- `planepnt::AbstractVector{<:Real}` – any point lying on the plane +- `raydir::AbstractVector{<:Real}` – direction vector of the line (need not be unit-length) +- `raypnt::AbstractVector{<:Real}` – any point lying on the line +# Returns +- `ψ::Vector{<:Real}` – coordinates of the intersection point +# Throws +- `ErrorException` if the line is parallel to the plane (no intersection or line lies in plane). +""" function intersectLineToPlane3D( - planenorm::AbstractVector{<:Real}, - planepnt::AbstractVector{<:Real}, - raydir::AbstractVector{<:Real}, - raypnt::AbstractVector{<:Real} -) - ndotu = dot(planenorm, raydir) - if ndotu ≈ 0 error("no intersection or line is within plane") end + planenorm::AbstractVector{<:Real}, + planepnt::AbstractVector{<:Real}, + raydir::AbstractVector{<:Real}, + raypnt::AbstractVector{<:Real} + ) + n_dot_u = dot(planenorm, raydir) + if n_dot_u ≈ 0 + error("no intersection or line is within plane") + end - w = raypnt - planepnt - si = -dot(planenorm, w) / ndotu - ψ = w .+ si .* raydir .+ planepnt + w = raypnt - planepnt + si = -dot(planenorm, w) / n_dot_u # ray parameter at intersection + ψ = w .+ si .* raydir .+ planepnt return ψ end @@ -149,31 +177,30 @@ l_Forb = intersectRayToPlane( See also: `CameraModels.intersectLineToPlane3D` """ function intersectRayToPlane( - c_H_a::AbstractMatrix{<:Real}, - a_F::AbstractVector{<:Real}, - l_nFL::AbstractVector{<:Real}, - l_FL::AbstractVector{<:Real}; - M = SpecialEuclidean(3), - R0 = [1 0 0; 0 1 0; 0 0 1.], - l_T_ex = ArrayPartition([0;0;0.], exp_lie(M.manifold[2], hat(M.manifold[2], R0, [0;0.2;0.]))), - ex_T_c = ArrayPartition([0;0;0.], [0 0 1; -1 0 0; 0 -1 0.]), -) + c_H_a::AbstractMatrix{<:Real}, + a_F::AbstractVector{<:Real}, + l_nFL::AbstractVector{<:Real}, + l_FL::AbstractVector{<:Real}; + M = SpecialEuclidean(3), + R0 = [1 0 0; 0 1 0; 0 0 1.0], + l_T_ex = ArrayPartition([0;0;0.0], exp_lie(M.manifold[2], hat(M.manifold[2], R0, [0;0.2;0.0]))), + ex_T_c = ArrayPartition([0;0;0.0], [0 0 1; -1 0 0; 0 -1 0.0]), + ) # camera in level (or camera to level) manifold element as ArrayPartition l_T_c = compose(M, l_T_ex, ex_T_c) - + ## convert pixel location to ray in camera then level frame c_F = c_H_a * a_F - # unit vector ray direction from camera in camera coordinates + # unit vector ray direction from camera in camera coordinates c_uV = c_F ./ norm(c_F) # get ray direction in level coordinates l_uV = l_T_c.x[2] * c_uV - + # and ray position from camera center in level frame l_P = l_T_c.x[1] - + ## planar floor surface projection l_nFL_ = l_nFL ./ norm(l_nFL) - - intersectLineToPlane3D(l_nFL_, l_FL, l_uV, l_P) # returns intersect in local level. -end + return intersectLineToPlane3D(l_nFL_, l_FL, l_uV, l_P) # returns intersect in local level. +end