Skip to content

Commit 9000a0b

Browse files
authored
Merge pull request #16 from JuliaRobotics/23Q1/enh/fixwarns
drop warns on load, fix tests
2 parents f8ed836 + 4b640d6 commit 9000a0b

File tree

6 files changed

+221
-198
lines changed

6 files changed

+221
-198
lines changed

NEWS.md

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,10 @@
11
# History of CameraModels.jl
22

3-
## v0.1.0
3+
## v0.2
4+
5+
- Remove method redefinition warnings by dropping additional types and keeping just construction helpers. Only types are `CameraCalibration[Mutable]`.
6+
- Consolidate type `CameraIntrinsic`
7+
## v0.1
48

59
- Created consolidated `CameraCalibration` type to replace various previous camera models (all doing about the same thing),
610
- Also `CameraCalibrationMutable` and `CameraCalibratonT` as the Union dispatch type.

Project.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
name = "CameraModels"
22
uuid = "0d57b887-6120-40e6-8b8c-29d3116bc0c1"
33
keywords = ["camera", "model", "pinhole", "distortion", "robotics", "images"]
4-
version = "0.1.1"
4+
version = "0.2.0"
55

66
[deps]
77
DocStringExtensions = "ffbed154-4ef7-542d-bbb7-c09d3a79fcae"

src/Deprecated.jl

Lines changed: 97 additions & 91 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,28 @@
66
## consolidated types below
77

88

9+
10+
# CameraCalibration(
11+
# height::Int= 480,
12+
# width::Int = 640,
13+
# center::Union{<:AbstractVector{<:Real},<:PixelCoordinate} = [width/2;height/2],
14+
# focal::AbstractVector{<:Real} = 1.1*[height; height], # just emperical default
15+
# kc::AbstractVector{<:Real} = SVector{5}(zeros(5)),
16+
# skew::Real = 0.0,
17+
# K::AbstractMatrix =[[focal[1];skew;center[1]]';[0.0;focal[2];center[2]]';[0.0;0;1]'],
18+
# ) = CameraCalibration(height, width, kc, SMatrix{3,3}(K), SMatrix{3,3}(inv(K)) )
19+
# CameraCalibrationMutable(;
20+
# width::Int = 640,
21+
# height::Int= 480,
22+
# center::Union{<:AbstractVector{<:Real},<:PixelCoordinate} = [width/2;height/2],
23+
# focal::AbstractVector{<:Real} = 1.1*[height; height], # just emperical default
24+
# kc::AbstractVector{<:Real} = MVector{5}(zeros(5)),
25+
# skew::Real = 0.0,
26+
# K::AbstractMatrix =[[focal[1];skew;center[1]]';[0.0;focal[2];center[2]]';[0.0;0;1]'],
27+
# ) = CameraCalibrationMutable(height, width, kc, MMatrix{3,3}(K), MMatrix{3,3}(inv(K)) )
28+
29+
30+
931
@deprecate point2pixel(model, pt) project(model, pt[[1;3;2]])
1032
@deprecate pixel2ray(model, px) backproject(model, px)[[1;3;2]]
1133

@@ -53,7 +75,7 @@ CameraModel = (@warn("CameraModels.CameraModel is deprecated, use CameraModels.A
5375
@deprecate columns(w...;kw...) width(w...;kw...)
5476
@deprecate rows(w...;kw...) height(w...;kw...)
5577

56-
sensorsize(cameramodel::CameraModel) = SVector{2}(width(cameramodel), height(cameramodel))
78+
# sensorsize(cameramodel::CameraModel) = SVector{2}(width(cameramodel), height(cameramodel))
5779

5880

5981
export CameraModelandParameters
@@ -71,27 +93,10 @@ function CameraModelandParameters(
7193
)
7294
#
7395
@warn("CameraModels.CameraModelandParameters is deprecated, use CamereModels.CameraCalibration instead.")
74-
CameraCalibration(;width,height,K)
96+
CameraCalibration(;width,height,K=SMatrix{3,3}(K))
7597
end
7698

7799

78-
function Base.getproperty(x::CameraModelandParameters, f::Symbol)
79-
if f == :skew
80-
getfield(x, :K)[1,2]
81-
elseif f == :columns
82-
getfield(x, :width)
83-
elseif f == :rows
84-
getfield(x, :height)
85-
elseif f == :prinicipalpoint || f == :cc
86-
SA[(getfield(x, :K)[1:2, 3])...]
87-
elseif f == :focallength || f == :fc
88-
K = getfield(x, :K)
89-
SA[K[1,1];K[2,2]]
90-
else
91-
getfield(x, f)
92-
end
93-
end
94-
95100

96101
# """
97102
# Data structure for a Camera model with parameters.
@@ -135,29 +140,28 @@ export PinholeCamera
135140
# end
136141

137142
## From JuliaRobotics/Caesar.jl
138-
const PinholeCamera = (@warn("CameraModels.PinholeCamera is deprecated, use CamereModels.CameraCalibrationMutable instead."); CameraCalibration)
143+
# const PinholeCamera = (@warn("CameraModels.PinholeCamera is deprecated, use CamereModels.CameraCalibrationMutable instead."); CameraCalibration)
139144

140145
function PinholeCamera(
141-
K_::AbstractMatrix=[[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor
142-
width::Int=round(Int, K_[1,3]*2),
143-
height::Int=round(Int, K_[2,3]*2),
144-
f_w::Real=K_[1,1],
145-
f_h::Real=K_[2,2],
146-
c_w::Real=K_[1,3],
147-
c_h::Real=K_[2,3],
148-
shear::Real=K_[1,2],
149-
K::AbstractMatrix=[[f_w;shear;c_w]';[0.0;f_h;c_h]';[0.0;0;1]'], # consolidated matrix K
150-
)
146+
K_::AbstractMatrix=[[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor
147+
width::Int=round(Int, K_[1,3]*2),
148+
height::Int=round(Int, K_[2,3]*2),
149+
f_w::Real=K_[1,1],
150+
f_h::Real=K_[2,2],
151+
c_w::Real=K_[1,3],
152+
c_h::Real=K_[2,3],
153+
shear::Real=K_[1,2],
154+
K::AbstractMatrix=[[f_w;shear;c_w]';[0.0;f_h;c_h]';[0.0;0;1]'], # consolidated matrix K
155+
)
151156
#
152157
@warn "CameraModels.PinholeCamera is deprecated, use CamereModels.CameraCalibrationMutable instead."
153158
if 3 < size(K_,1)
154159
@warn "PinholeCamera(arg), 3 < size(arg,1), assuming legacy constructor as img as input argument."
155160
return CameraCalibrationMutable(K_) # as though img=K_
156161
end
157-
CameraCalibrationMutable(;width,height,K)
162+
CameraCalibrationMutable(;width,height,K=MMatrix{3,3}(K))
158163
end
159164

160-
161165
# @deprecate PinholeCamera(img::AbstractMatrix) CameraCalibrationMutable(img)
162166

163167
# function PinholeCamera(img::AbstractMatrix{T}) where T
@@ -168,17 +172,17 @@ end
168172
# end
169173

170174

171-
f_w(pc::PinholeCamera) = pc.K[1,1]
172-
f_h(pc::PinholeCamera) = pc.K[2,2]
173-
shear(pc::PinholeCamera) = pc.K[1,2]
174-
c_w(pc::PinholeCamera) = pc.K[1,3]
175-
c_h(pc::PinholeCamera) = pc.K[2,3]
175+
# f_w(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[1,1]
176+
# f_h(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[2,2]
177+
# shear(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[1,2]
178+
# c_w(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[1,3]
179+
# c_h(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[2,3]
176180

177-
set_f_w!(pc::PinholeCamera, val::Real) = (pc.K[1,1] = val)
178-
set_f_h!(pc::PinholeCamera, val::Real) = (pc.K[2,2] = val)
179-
set_shear!(pc::PinholeCamera, val::Real) = (pc.K[1,2] = val)
180-
set_c_w!(pc::PinholeCamera, val::Real) = (pc.K[1,3] = val)
181-
set_c_h!(pc::PinholeCamera, val::Real) = (pc.K[2,3] = val)
181+
# set_f_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,1] = val)
182+
# set_f_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,2] = val)
183+
# set_shear!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,2] = val)
184+
# set_c_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,3] = val)
185+
# set_c_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,3] = val)
182186

183187

184188
export Pinhole
@@ -188,28 +192,73 @@ export Pinhole
188192
const Pinhole = (@warn("CameraModels.Pinhole is deprecated, use CamereModels.CameraCalibration instead."); CameraCalibration)
189193
function Pinhole(columns::Int,rows::Int,prinicipalpoint,focallength::Vector2 )
190194
@warn "CameraModels.Pinhole is deprecated, use CamereModels.CameraCalibration instead."
195+
f_w,f_h = focallength[1], focallength[2]
196+
c_w,c_h = prinicipalpoint[1], prinicipalpoint[2]
197+
K = SMatrix{3,3}([[f_w;0.0;c_w]';[0.0;f_h;c_h]';[0.0;0;1.]'] )
191198
CameraCalibration(;
192199
height=rows,
193200
width=columns,
194-
center=prinicipalpoint,
195-
focal=focallength
201+
K
196202
)
197203
end
198204

199-
function Base.getproperty(x::Pinhole, f::Symbol)
200-
if f == :columns
205+
function CameraIntrinsic(
206+
K_::AbstractMatrix=[[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor
207+
x0=320.0,y0=240.0,fx=510.0,fy=510.0,s=0.0, # legacy function support
208+
K::AbstractMatrix=[[fx;s;x0]';[0.0;fy;y0]';[0.0;0;1]'], # consolidated matrix K
209+
width::Int=round(Int, K[1,3]*2),
210+
height::Int=round(Int, K[2,3]*2),
211+
)
212+
#
213+
@warn "CameraModels.CameraIntrinsic is deprecated, use CamereModels.CameraCalibration instead."
214+
CameraCalibration(;width,height,K)
215+
end
216+
export CameraIntrinsic
217+
218+
# Base.@kwdef struct CameraIntrinsic
219+
# K::Array{Float64,2}
220+
# end
221+
# CameraIntrinsic(;x0=320.0,y0=240.0,fx=510.0,fy=510.0,s=0.0) = CameraIntrinsic([[fx;s;x0]';[0.0;fy;y0]';[0.0;0;1]'])
222+
223+
## From JuliaRobotics/Caesar.jl
224+
# const CameraIntrinsic = (@warn("CameraModels.CameraIntrinsic is deprecated, use CamereModels.CameraCalibration instead.");CameraCalibration)
225+
226+
227+
function Base.getproperty(
228+
x::Union{<:Pinhole, CameraModelandParameters},
229+
f::Symbol,
230+
)
231+
if f == :skew
232+
getfield(x, :K)[1,2]
233+
elseif f == :columns
201234
getfield(x, :width)
202235
elseif f == :rows
203236
getfield(x, :height)
204-
elseif f == :prinicipalpoint
237+
elseif f == :prinicipalpoint || f == :cc
205238
SA[(getfield(x, :K)[1:2, 3])...]
206-
elseif f == :focallength
239+
elseif f == :focallength || f == :fc
207240
K = getfield(x, :K)
208241
SA[K[1,1];K[2,2]]
209242
else
210243
getfield(x, f)
211244
end
212245
end
246+
# function Base.getproperty(x::CameraModelandParameters, f::Symbol)
247+
# if f == :skew
248+
# getfield(x, :K)[1,2]
249+
# elseif f == :columns
250+
# getfield(x, :width)
251+
# elseif f == :rows
252+
# getfield(x, :height)
253+
# elseif f == :prinicipalpoint || f == :cc
254+
# SA[(getfield(x, :K)[1:2, 3])...]
255+
# elseif f == :focallength || f == :fc
256+
# K = getfield(x, :K)
257+
# SA[K[1,1];K[2,2]]
258+
# else
259+
# getfield(x, f)
260+
# end
261+
# end
213262

214263
# ## From yakir12/CameraModels.jl
215264
# struct Pinhole <: CameraModel
@@ -222,49 +271,6 @@ end
222271

223272

224273

225-
export CameraIntrinsic
226-
227-
# Base.@kwdef struct CameraIntrinsic
228-
# K::Array{Float64,2}
229-
# end
230-
# CameraIntrinsic(;x0=320.0,y0=240.0,fx=510.0,fy=510.0,s=0.0) = CameraIntrinsic([[fx;s;x0]';[0.0;fy;y0]';[0.0;0;1]'])
231-
232-
## From JuliaRobotics/Caesar.jl
233-
const CameraIntrinsic = (@warn("CameraModels.CameraIntrinsic is deprecated, use CamereModels.CameraCalibration instead.");CameraCalibration)
234-
235-
function CameraIntrinsic(
236-
K_::AbstractMatrix=[[510;0;320.0]';[0.0;510;240]';[0.0;0;1]']; # legacy constructor
237-
x0=320.0,y0=240.0,fx=510.0,fy=510.0,s=0.0, # legacy function support
238-
K::AbstractMatrix=[[fx;s;x0]';[0.0;fy;y0]';[0.0;0;1]'], # consolidated matrix K
239-
width::Int=round(Int, K[1,3]*2),
240-
height::Int=round(Int, K[2,3]*2),
241-
)
242-
#
243-
@warn "CameraModels.CameraIntrinsic is deprecated, use CamereModels.CameraCalibration instead."
244-
CameraCalibration(;width,height,K)
245-
end
246-
247-
248-
249-
250-
251-
## ===========================================================================
252-
## Legacy types that are not so easy to consolidate (not exported) DO NOT USE
253-
## ===========================================================================
254-
255-
256-
# Camera extrinsic must be world in camera frame (cRw)
257-
Base.@kwdef struct CameraExtrinsic{T <: Real}
258-
R::SMatrix{3,3,T} = id = one(Rot_.RotMatrix{3, Float64}).mat
259-
t::Vector{T} = zeros(3)
260-
end
261-
262-
Base.@kwdef struct CameraModelFull
263-
ci::CameraIntrinsic = CameraIntrinsic()
264-
ce::CameraExtrinsic = CameraExtrinsic()
265-
end
266-
267-
268274

269275

270276
#

src/entities/CameraCalibration.jl

Lines changed: 34 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -33,17 +33,17 @@ DevNotes
3333
3434
Also see: [`CameraCalibrationT`](@ref) [`CameraCalibrationMutable`](@ref), (TODO: `ProjectiveCameraModel`)
3535
"""
36-
struct CameraCalibration{R <: Real,N} <: AbstractCameraModel
37-
""" numver of pixels from top to bottom """
38-
height::Int # = 480
36+
Base.@kwdef struct CameraCalibration{R <: Real,N} <: AbstractCameraModel
37+
""" number of pixels from top to bottom """
38+
height::Int = 480
3939
""" number of pixels from left to right """
40-
width::Int # = 640
40+
width::Int = 640
4141
""" distortion coefficients up to fifth order """
42-
kc::SVector{N,R} # = zeros(5)
42+
kc::SVector{N,R} = SVector(zeros(5)...)
4343
""" 3x3 camera calibration matrix """
44-
K::SMatrix{3,3,R} # = SMatrix{3,3}([[height;0.0;width/2]';[0.0;height;height/2]';[0.0;0;1]'] )
44+
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.]'] )
4545
""" inverse of a 3x3 camera calibration matrix """
46-
Ki::SMatrix{3,3,R} # = inv(K)
46+
Ki::SMatrix{3,3,R,9} = inv(K)
4747
end
4848

4949

@@ -52,19 +52,20 @@ end
5252
5353
See [`CameraCalibraton`](@ref).
5454
"""
55-
mutable struct CameraCalibrationMutable{R <: Real,N} <: AbstractCameraModel
56-
""" numver of pixels from top to bottom """
57-
height::Int # = 480
55+
Base.@kwdef mutable struct CameraCalibrationMutable{R <: Real,N} <: AbstractCameraModel
56+
""" number of pixels from top to bottom """
57+
height::Int = 480
5858
""" number of pixels from left to right """
59-
width::Int # = 640
59+
width::Int = 640
6060
""" distortion coefficients up to fifth order """
61-
kc::MVector{N,R} # = zeros(5)
61+
kc::MVector{N,R} = MVector(zeros(5)...)
6262
""" 3x3 camera calibration matrix """
63-
K::MMatrix{3,3,R} # = SMatrix{3,3}([[height;0.0;width/2]';[0.0;height;height/2]';[0.0;0;1]'] )
63+
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.]'] )
6464
""" inverse of a 3x3 camera calibration matrix """
65-
Ki::MMatrix{3,3,R} # = inv(K)
65+
Ki::MMatrix{3,3,R} = inv(K)
6666
end
6767

68+
6869
"""
6970
CameraCalibrationT
7071
@@ -74,4 +75,23 @@ CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable}
7475

7576

7677

78+
## ===========================================================================
79+
## Legacy types that are not so easy to consolidate (not exported) DO NOT USE
80+
## ===========================================================================
81+
82+
83+
# Camera extrinsic must be world in camera frame (cRw)
84+
Base.@kwdef struct CameraExtrinsic{T <: Real}
85+
R::SMatrix{3,3,T,9} = one(Rot_.RotMatrix{3, Float64}).mat
86+
t::SVector{3,T} = SVector(0,0,0.)
87+
end
88+
89+
Base.@kwdef struct CameraModelFull
90+
ci::CameraCalibration = CameraCalibration()
91+
ce::CameraExtrinsic = CameraExtrinsic()
92+
end
93+
94+
95+
96+
7797
#

0 commit comments

Comments
 (0)