Skip to content

Commit 1c1da79

Browse files
thimotedupuchThimoté DupuchAffie
authored
Small changes (#34)
* Formatting via Runic.jl * improved docs for intersectLineToPlane3D + getindex refactoring * CPU imlementation for radialDistortion! with @tturbo * add LoopVectorization to the project's dependencies * Refactor + test for radialDistortion! --------- Co-authored-by: Thimoté Dupuch <thimote.dupuch@proton.me> Co-authored-by: Johannes Terblanche <6612981+Affie@users.noreply.github.com>
1 parent 8f0cda2 commit 1c1da79

File tree

12 files changed

+406
-370
lines changed

12 files changed

+406
-370
lines changed

Project.toml

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,20 @@
11
name = "CameraModels"
22
uuid = "0d57b887-6120-40e6-8b8c-29d3116bc0c1"
3-
keywords = ["camera", "model", "pinhole", "distortion", "robotics", "images"]
3+
keywords = ["camera", "model", "pinhole", "distortion", "robotics", "images", "vision"]
44
version = "0.2.4"
55

66
[deps]
77
DocStringExtensions = "ffbed154-4ef7-542d-bbb7-c09d3a79fcae"
88
LieGroups = "6774de46-80ba-43f8-ba42-e41071ccfc5f"
99
LinearAlgebra = "37e2e46d-f89d-539d-b4ee-838fcccc9c8e"
10+
LoopVectorization = "bdcacae8-1622-11e9-2a5c-532679323890"
1011
RecursiveArrayTools = "731186ca-8d62-57ce-b412-fbd966d074cd"
1112
Rotations = "6038ab10-8711-5258-84ad-4b1120ba62dc"
1213
StaticArrays = "90137ffa-7385-5640-81b9-e52037218182"
1314

1415
[compat]
1516
DocStringExtensions = "0.8, 0.9"
17+
LoopVectorization = "0.12.173"
1618
LieGroups = "0.1"
1719
RecursiveArrayTools = "3.27.0"
1820
Rotations = "1"

src/CameraModels.jl

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ using StaticArrays
77
import Rotations as Rot_
88
import Base: getindex, getproperty, show
99
using RecursiveArrayTools: ArrayPartition
10+
using LoopVectorization: @tturbo
1011

1112
# exports
1213
include("ExportAPI.jl")
@@ -26,6 +27,4 @@ include("services/CameraServices.jl")
2627
include("services/Utils.jl")
2728

2829

29-
30-
3130
end # module

src/Deprecated.jl

Lines changed: 79 additions & 86 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,11 @@
1-
21
## ================================================================================================
32
## consolidated types from various repos in Julia ecosystem
43
## ================================================================================================
54

6-
@deprecate project(cm::CameraModelFull, pt::AbstractVector{<:Real}) project(cm.ci,pt) # drops extrinsics
5+
@deprecate project(cm::CameraModelFull, pt::AbstractVector{<:Real}) project(cm.ci, pt) # drops extrinsics
76

87
# function project(
9-
# cm::CameraModelFull,
8+
# cm::CameraModelFull,
109
# pt::AbstractVector{<:Real}
1110
# )
1211
# res = Vector{Float64}(2)
@@ -21,7 +20,7 @@ A Union type for users to implement against both `struct`` and `mutable struct`
2120
"""
2221
CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable}
2322

24-
@deprecate CameraExtrinsic(R::AbstractMatrix=[1 0 0; 0 1 0; 0 0 1.], t::AbstractVector=[0,0,0.]) ArrayPartition(SVector(t...),SMatrix(R))
23+
@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))
2524

2625
# Camera extrinsic must be world in camera frame (cRw)
2726
# Base.@kwdef struct CameraExtrinsic{T <: Real}
@@ -30,7 +29,7 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable}
3029
# end
3130

3231

33-
@deprecate PixelCoordinate(row,col) PixelIndex(row,col)
32+
@deprecate PixelCoordinate(row, col) PixelIndex(row, col)
3433

3534
# CameraCalibration(
3635
# height::Int= 480,
@@ -52,7 +51,6 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable}
5251
# ) = CameraCalibrationMutable(height, width, kc, MMatrix{3,3}(K), MMatrix{3,3}(inv(K)) )
5352

5453

55-
5654
@deprecate point2pixel(model, pt) project(model, pt[[1;3;2]])
5755
@deprecate pixel2ray(model, px) backproject(model, px)[[1;3;2]]
5856

@@ -61,7 +59,7 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable}
6159
# point2pixel(model::Pinhole, pointincamera::$(Point3))
6260

6361
# Return a transformation that converts real-world coordinates
64-
# to camera coordinates. This currently ignores any tangential
62+
# to camera coordinates. This currently ignores any tangential
6563
# distortion between the lens and the image plane.
6664
# """
6765
# function point2pixel(model::CameraCalibrationT, pointincamera::Point3)
@@ -75,7 +73,7 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable}
7573
# pixel2ray(model::Pinhole, pixelcoordinate::$(PixelCoordinate))
7674

7775
# Return a transformation that converts real-world coordinates
78-
# to camera coordinates. This currently ignores any tangential
76+
# to camera coordinates. This currently ignores any tangential
7977
# distortion between the lens and the image plane.
8078
# """
8179
# function pixel2ray(model::CameraCalibrationT, pixelcoordinate::PixelCoordinate)
@@ -86,19 +84,19 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable}
8684

8785

8886
export CameraModel # being replaced by AbstractCameraModel
89-
CameraModel = (@warn("CameraModels.CameraModel is deprecated, use CameraModels.AbstractCameraModel instead");AbstractCameraModel)
90-
# abstract type CameraModel end
87+
CameraModel = (@warn("CameraModels.CameraModel is deprecated, use CameraModels.AbstractCameraModel instead"); AbstractCameraModel)
88+
# abstract type CameraModel end
9189

9290
@warn "RadialDistortion is deprecated, use CameraCalibration instead"
9391
# Base.@kwdef struct RadialDistortion{N, R <: Real, K <: AbstractVector}
94-
# Ki::SVector{N,R} = SVector(0.0) #
92+
# Ki::SVector{N,R} = SVector(0.0) #
9593
# center::SVector{2,R} = SVector{2,R}(0.0,0.0) # SVector{2,R} # [h,w]
9694
# # _radius2::Matrix{R} # perhaps SizedArray{R,2} or StaticArray{R,2} or GPUArray{R,2} depending on performance
9795
# end
9896

9997

100-
@deprecate columns(w...;kw...) width(w...;kw...)
101-
@deprecate rows(w...;kw...) height(w...;kw...)
98+
@deprecate columns(w...; kw...) width(w...; kw...)
99+
@deprecate rows(w...; kw...) height(w...; kw...)
102100

103101
# sensorsize(cameramodel::CameraModel) = SVector{2}(width(cameramodel), height(cameramodel))
104102

@@ -107,22 +105,21 @@ export CameraModelandParameters
107105
# const CameraModelandParameters = (@warn("CameraModels.CameraModelandParameters is deprecated, use CameraModels.CameraCalibration instead.");CameraCalibration)
108106

109107
function CameraModelandParameters(
110-
width::Int,
111-
height::Int,
112-
fc::AbstractVector{<:Real},
113-
cc::AbstractVector{<:Real},
114-
skew::Real,
115-
kc::AbstractVector{<:Real},
116-
K::AbstractMatrix{<:Real} = [[fc[1];skew;cc[1]]';[0.0;fc[2];cc[2]]';[0.0;0;1]'], # legacy constructor
117-
Ki::AbstractMatrix{<:Real} = inv(K)
118-
)
119-
#
120-
@warn("CameraModels.CameraModelandParameters is deprecated, use CameraModels.CameraCalibration instead.")
121-
CameraCalibration(;width,height,K=SMatrix{3,3}(K))
108+
width::Int,
109+
height::Int,
110+
fc::AbstractVector{<:Real},
111+
cc::AbstractVector{<:Real},
112+
skew::Real,
113+
kc::AbstractVector{<:Real},
114+
K::AbstractMatrix{<:Real} = [[fc[1];skew;cc[1]]';[0.0;fc[2];cc[2]]';[0.0;0;1]'], # legacy constructor
115+
Ki::AbstractMatrix{<:Real} = inv(K)
116+
)
117+
#
118+
@warn("CameraModels.CameraModelandParameters is deprecated, use CameraModels.CameraCalibration instead.")
119+
return CameraCalibration(; width, height, K = SMatrix{3, 3}(K))
122120
end
123121

124122

125-
126123
# """
127124
# Data structure for a Camera model with parameters.
128125
# Use `CameraModel(width,height,fc,cc,skew,kc)` for easy construction.
@@ -139,7 +136,6 @@ end
139136
# end
140137

141138

142-
143139
export PinholeCamera
144140

145141
# ## From JuliaRobotics/Caesar.jl
@@ -152,7 +148,7 @@ export PinholeCamera
152148
# - https://en.wikipedia.org/wiki/Pinhole_camera
153149
# - Standard Julia *[Images.jl](https://juliaimages.org/latest/)-frame* convention is, `size(img) <==> (i,j) <==> (height,width) <==> (y,x)`,
154150
# - Common *camera-frame* in computer vision and robotics, `(x,y) <==> (width,height) <==> (j,i)`,
155-
# - Using top left corner of image as `(0,0)` in all cases.
151+
# - Using top left corner of image as `(0,0)` in all cases.
156152
# - Direct comparison with [OpenCV convention](https://docs.opencv.org/3.4/d9/d0c/group__calib3d.html) is:
157153
# - `(x,y) [CamXYZ] <==> (j,i) [Images.jl] <==> (u,v) [OpenCV]` -- look very carfully at `(u,v) <==> (j,i)` in *image-frame*
158154
# - Always follow right hand rule for everything.
@@ -168,23 +164,23 @@ export PinholeCamera
168164
# const PinholeCamera = (@warn("CameraModels.PinholeCamera is deprecated, use CameraModels.CameraCalibrationMutable instead."); CameraCalibration)
169165

170166
function PinholeCamera(
171-
K_::AbstractMatrix=[[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor
172-
width::Int=round(Int, K_[1,3]*2),
173-
height::Int=round(Int, K_[2,3]*2),
174-
f_w::Real=K_[1,1],
175-
f_h::Real=K_[2,2],
176-
c_w::Real=K_[1,3],
177-
c_h::Real=K_[2,3],
178-
shear::Real=K_[1,2],
179-
K::AbstractMatrix=[[f_w;shear;c_w]';[0.0;f_h;c_h]';[0.0;0;1]'], # consolidated matrix K
180-
)
181-
#
182-
@warn "CameraModels.PinholeCamera is deprecated, use CameraModels.CameraCalibrationMutable instead."
183-
if 3 < size(K_,1)
184-
@warn "PinholeCamera(arg), 3 < size(arg,1), assuming legacy constructor as img as input argument."
185-
return CameraCalibrationMutable(K_) # as though img=K_
186-
end
187-
CameraCalibrationMutable(;width,height,K=MMatrix{3,3}(K))
167+
K_::AbstractMatrix = [[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor
168+
width::Int = round(Int, K_[1, 3] * 2),
169+
height::Int = round(Int, K_[2, 3] * 2),
170+
f_w::Real = K_[1, 1],
171+
f_h::Real = K_[2, 2],
172+
c_w::Real = K_[1, 3],
173+
c_h::Real = K_[2, 3],
174+
shear::Real = K_[1, 2],
175+
K::AbstractMatrix = [[f_w;shear;c_w]';[0.0;f_h;c_h]';[0.0;0;1]'], # consolidated matrix K
176+
)
177+
#
178+
@warn "CameraModels.PinholeCamera is deprecated, use CameraModels.CameraCalibrationMutable instead."
179+
if 3 < size(K_, 1)
180+
@warn "PinholeCamera(arg), 3 < size(arg,1), assuming legacy constructor as img as input argument."
181+
return CameraCalibrationMutable(K_) # as though img=K_
182+
end
183+
return CameraCalibrationMutable(; width, height, K = MMatrix{3, 3}(K))
188184
end
189185

190186
# @deprecate PinholeCamera(img::AbstractMatrix) CameraCalibrationMutable(img)
@@ -216,28 +212,28 @@ export Pinhole
216212

217213
## From yakir12/CameraModels.jl
218214
# const Pinhole = (@warn("CameraModels.Pinhole is deprecated, use CameraModels.CameraCalibration instead."); CameraCalibration)
219-
function Pinhole(columns::Int,rows::Int,prinicipalpoint,focallength::Vector2 )
220-
@warn "CameraModels.Pinhole is deprecated, use CameraModels.CameraCalibration instead."
221-
f_w,f_h = focallength[1], focallength[2]
222-
c_w,c_h = prinicipalpoint[1], prinicipalpoint[2]
223-
K = SMatrix{3,3}([[f_w;0.0;c_w]';[0.0;f_h;c_h]';[0.0;0;1.]'] )
224-
CameraCalibration(;
225-
height=rows,
226-
width=columns,
227-
K
228-
)
215+
function Pinhole(columns::Int, rows::Int, prinicipalpoint, focallength::Vector2)
216+
@warn "CameraModels.Pinhole is deprecated, use CameraModels.CameraCalibration instead."
217+
f_w, f_h = focallength[1], focallength[2]
218+
c_w, c_h = prinicipalpoint[1], prinicipalpoint[2]
219+
K = SMatrix{3, 3}([[f_w;0.0;c_w]';[0.0;f_h;c_h]';[0.0;0;1.0]'])
220+
return CameraCalibration(;
221+
height = rows,
222+
width = columns,
223+
K
224+
)
229225
end
230226

231227
function CameraIntrinsic(
232-
K_::AbstractMatrix=[[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor
233-
x0=320.0,y0=240.0,fx=510.0,fy=510.0,s=0.0, # legacy function support
234-
K::AbstractMatrix=[[fx;s;x0]';[0.0;fy;y0]';[0.0;0;1]'], # consolidated matrix K
235-
width::Int=round(Int, K[1,3]*2),
236-
height::Int=round(Int, K[2,3]*2),
237-
)
238-
#
239-
@warn "CameraModels.CameraIntrinsic is deprecated, use CameraModels.CameraCalibration instead."
240-
CameraCalibration(;width,height,K)
228+
K_::AbstractMatrix = [[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor
229+
x0 = 320.0, y0 = 240.0, fx = 510.0, fy = 510.0, s = 0.0, # legacy function support
230+
K::AbstractMatrix = [[fx;s;x0]';[0.0;fy;y0]';[0.0;0;1]'], # consolidated matrix K
231+
width::Int = round(Int, K[1, 3] * 2),
232+
height::Int = round(Int, K[2, 3] * 2),
233+
)
234+
#
235+
@warn "CameraModels.CameraIntrinsic is deprecated, use CameraModels.CameraCalibration instead."
236+
return CameraCalibration(; width, height, K)
241237
end
242238
export CameraIntrinsic
243239

@@ -251,23 +247,23 @@ export CameraIntrinsic
251247

252248

253249
function Base.getproperty(
254-
x::CameraCalibration, # Union{<:Pinhole, CameraModelandParameters},
255-
f::Symbol,
256-
)
257-
if f == :skew
258-
getfield(x, :K)[1,2]
259-
elseif f == :columns
260-
getfield(x, :width)
261-
elseif f == :rows
262-
getfield(x, :height)
263-
elseif f == :prinicipalpoint || f == :cc
264-
SA[(getfield(x, :K)[1:2, 3])...]
265-
elseif f == :focallength || f == :fc
266-
K = getfield(x, :K)
267-
SA[K[1,1];K[2,2]]
268-
else
269-
getfield(x, f)
270-
end
250+
x::CameraCalibration, # Union{<:Pinhole, CameraModelandParameters},
251+
f::Symbol,
252+
)
253+
return if f == :skew
254+
getfield(x, :K)[1, 2]
255+
elseif f == :columns
256+
getfield(x, :width)
257+
elseif f == :rows
258+
getfield(x, :height)
259+
elseif f == :prinicipalpoint || f == :cc
260+
SA[(getfield(x, :K)[1:2, 3])...]
261+
elseif f == :focallength || f == :fc
262+
K = getfield(x, :K)
263+
SA[K[1, 1];K[2, 2]]
264+
else
265+
getfield(x, f)
266+
end
271267
end
272268
# function Base.getproperty(x::CameraModelandParameters, f::Symbol)
273269
# if f == :skew
@@ -280,7 +276,7 @@ end
280276
# SA[(getfield(x, :K)[1:2, 3])...]
281277
# elseif f == :focallength || f == :fc
282278
# K = getfield(x, :K)
283-
# SA[K[1,1];K[2,2]]
279+
# SA[K[1,1];K[2,2]]
284280
# else
285281
# getfield(x, f)
286282
# end
@@ -296,7 +292,4 @@ end
296292
# end
297293

298294

299-
300-
301-
302-
#
295+
#

src/ExportAPI.jl

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,3 @@
1-
2-
3-
41
export AbstractCameraModel
52

63
export CameraCalibration, CameraCalibrationMutable
@@ -10,7 +7,7 @@ export CameraSkewDistortion
107

118
export undistortPoint
129
export Ray, PixelIndex
13-
export pixel2ray, point2pixel, canreproject, sensorsize #, origin, direction,
10+
export pixel2ray, point2pixel, canreproject, sensorsize #, origin, direction,
1411
export project, projectHomogeneous
1512
export backproject, backprojectHomogeneous
1613
export pp_w, pp_h, f_w, f_h
@@ -21,4 +18,4 @@ export intersectLineToPlane3D, intersectRayToPlane
2118

2219
# suppressing super general signatures likely to have conflicts.
2320
# TODO adopt common Julia definition for points and vectors, maybe something from JuliaGeometry, etc.
24-
# export Vector3, Vector2, Point3
21+
# export Vector3, Vector2, Point3

0 commit comments

Comments
 (0)