Skip to content

Commit ce9ba3e

Browse files
authored
Merge pull request #18 from JuliaRobotics/23Q1/depr/dropcamcalT
drop CameraCalibrationT
2 parents 3e7ffbf + 85fdf79 commit ce9ba3e

File tree

5 files changed

+30
-25
lines changed

5 files changed

+30
-25
lines changed

src/Deprecated.jl

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,15 @@
55
## ================================================================================================
66
## consolidated types below
77

8+
export CameraCalibrationT
9+
10+
"""
11+
CameraCalibrationT
12+
13+
A Union type for users to implement against both `struct`` and `mutable struct` definitions of `CameraCalibration`
14+
"""
15+
CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable}
16+
817
@deprecate CameraExtrinsic(R::AbstractMatrix=[1 0 0; 0 1 0; 0 0 1.], t::AbstractVector=[0,0,0.]) ArrayPartition(SVector(t...),SMatrix(R))
918

1019
# Camera extrinsic must be world in camera frame (cRw)

src/ExportAPI.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33

44
export AbstractCameraModel
55

6-
export CameraCalibrationT, CameraCalibration, CameraCalibrationMutable
6+
export CameraCalibration, CameraCalibrationMutable
77

88
export CameraSkewDistortion
99

src/entities/CameraCalibration.jl

Lines changed: 2 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -25,13 +25,13 @@ Notes
2525
- Direct comparison with [OpenCV convention](https://docs.opencv.org/3.4/d9/d0c/group__calib3d.html) is:
2626
- `(x,y) [CamXYZ] <==> (j,i) [Images.jl] <==> (u,v) [OpenCV]` -- look very carfully at `(u,v) <==> (j,i)` in *image-frame*
2727
- Always follow right hand rule for everything.
28-
- A convenience Union type [`CameraCalibrationT`](@ref) is provided to develop implementations against `struct` and `mutable struct` types.
28+
- An abstract type [`AbstractCameraModel`](@ref) is provided to develop implementations against `struct` and `mutable struct` types.
2929
3030
DevNotes
3131
- https://en.wikipedia.org/wiki/Distortion_(optics)
3232
3333
34-
Also see: [`CameraCalibrationT`](@ref) [`CameraCalibrationMutable`](@ref), (TODO: `ProjectiveCameraModel`)
34+
Also see: [`AbstractCameraModel`](@ref) [`CameraCalibrationMutable`](@ref), (TODO: `ProjectiveCameraModel`)
3535
"""
3636
Base.@kwdef struct CameraCalibration{R <: Real,N} <: AbstractCameraModel
3737
""" number of pixels from top to bottom """
@@ -66,12 +66,6 @@ Base.@kwdef mutable struct CameraCalibrationMutable{R <: Real,N} <: AbstractCame
6666
end
6767

6868

69-
"""
70-
CameraCalibrationT
71-
72-
A Union type for users to implement against both `struct`` and `mutable struct` definitions of `CameraCalibration`
73-
"""
74-
CameraCalibrationT = Union{<:CameraCalibration, <:CameraCalibrationMutable}
7569

7670

7771

src/services/CameraServices.jl

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -7,10 +7,10 @@
77
## From yakir12/CameraModels.jl
88
origin(vector::Union{<:AbstractVector{<:Real},<:Vector3}) = origin3d
99
origin(ray::Ray) = ray.origin
10-
lookdirection(cameramodel::CameraCalibrationT) = SVector{3}(0,1,0)
11-
updirection(cameramodel::CameraCalibrationT) = SVector{3}(0,0,1)
12-
width(cameramodel::CameraCalibrationT) = cameramodel.width
13-
height(cameramodel::CameraCalibrationT) = cameramodel.height
10+
lookdirection(cameramodel::AbstractCameraModel) = SVector{3}(0,1,0)
11+
updirection(cameramodel::AbstractCameraModel) = SVector{3}(0,0,1)
12+
width(cameramodel::AbstractCameraModel) = cameramodel.width
13+
height(cameramodel::AbstractCameraModel) = cameramodel.height
1414
direction(vector::Union{<:AbstractVector{<:Real},<:Vector3}) = vector
1515
direction(ray::Ray) = ray.direction
1616
sensorsize(cameramodel::AbstractCameraModel) = SVector{2}(width(cameramodel), height(cameramodel))
@@ -24,11 +24,11 @@ canreproject(camera::AbstractCameraModel) = true
2424

2525

2626
## From JuliaRobotics/Caesar.jl
27-
f_w(pc::CameraCalibrationT) = pc.K[1,1]
28-
f_h(pc::CameraCalibrationT) = pc.K[2,2]
29-
shear(pc::CameraCalibrationT) = pc.K[1,2]
30-
c_w(pc::CameraCalibrationT) = pc.K[1,3]
31-
c_h(pc::CameraCalibrationT) = pc.K[2,3]
27+
f_w(pc::AbstractCameraModel) = pc.K[1,1]
28+
f_h(pc::AbstractCameraModel) = pc.K[2,2]
29+
shear(pc::AbstractCameraModel) = pc.K[1,2]
30+
c_w(pc::AbstractCameraModel) = pc.K[1,3]
31+
c_h(pc::AbstractCameraModel) = pc.K[2,3]
3232

3333
set_f_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,1] = val)
3434
set_f_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,2] = val)
@@ -59,13 +59,13 @@ Deprecates:
5959
Also see: [`backproject`](@ref)
6060
"""
6161
function project(
62-
model::CameraCalibrationT,
62+
model::AbstractCameraModel,
6363
pointincamera::Union{<:AbstractVector{<:Real}, <:Point3}
6464
)
6565
#
6666
column = c_w(model) + f_w(model) * pointincamera[1] / pointincamera[3]
6767
row = c_h(model) - f_h(model) * pointincamera[2] / pointincamera[3]
68-
return PixelCoordinate(column, row)
68+
return PixelIndex(column, row)
6969
end
7070
## homogeneous point coords xyzw (stereo cameras)
7171
# # xyzw are in the camera frame, i.e. x-columns, y-rows, z-forward
@@ -95,9 +95,9 @@ Deprecates:
9595
Also see: [`project`](@ref)
9696
"""
9797
function backproject(
98-
model::CameraCalibrationT,
99-
px_coord::Union{<:AbstractVector{<:Real}, <:PixelIndex}
100-
)
98+
model::AbstractCameraModel, # AbstractCameraModel,
99+
px_coord::Union{<:AbstractVector{<:Real}, <:PixelIndex}
100+
)
101101
#
102102
x = (px_coord[1] - c_w(model)) / f_w(model)
103103
y = -(px_coord[2] - c_h(model)) / f_h(model)

src/services/Prototypes.jl

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,18 +37,20 @@ Return the size of the camera sensor. By default calling out to columns(model) a
3737
function sensorsize end
3838

3939
"""
40-
pixel2ray(cameramodel::AbstractCameraModel, pixelcoordinate::$(PixelCoordinate))
40+
pixel2ray(cameramodel::AbstractCameraModel, pixelIndex::$(PixelIndex))
4141
42-
Returns the ray in space (origin + direction) corresponding to this `pixelcoordinate`.
42+
Returns the ray in space (origin + direction) corresponding to this `pixelIndex`.
4343
"""
4444
function pixel2ray end
45+
function backproject end
4546

4647
"""
4748
point2pixel(camera::AbstractCameraModel, pointincamera::$(Point3))
4849
4950
Returns the pixel location onto which the 3D coordinate `pointincamera` is projected.
5051
"""
5152
function point2pixel end
53+
function project end
5254

5355
"""
5456
lookdirection(camera::AbstractCameraModel)

0 commit comments

Comments
 (0)