Skip to content

Commit 0d59140

Browse files
committed
more standard functions
1 parent 7bd32da commit 0d59140

File tree

3 files changed

+71
-65
lines changed

3 files changed

+71
-65
lines changed

src/Deprecated.jl

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,8 @@
11

2-
3-
4-
52
## ================================================================================================
6-
## consolidated types below
3+
## consolidated types from various repos in Julia ecosystem
4+
## ================================================================================================
75

8-
export CameraCalibrationT
96

107
"""
118
CameraCalibrationT
@@ -189,18 +186,19 @@ end
189186
# PinholeCamera(;f_w, f_h, c_w, c_h)
190187
# end
191188

192-
189+
@deprecate c_w(w...) pp_w(w...)
190+
@deprecate c_h(w...) pp_h(w...)
193191
# f_w(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[1,1]
194192
# f_h(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[2,2]
195193
# shear(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[1,2]
196-
# c_w(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[1,3]
197-
# c_h(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[2,3]
194+
# pp_w(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[1,3]
195+
# pp_h(pc::Union{CameraCalibration,CameraCalibrationMutable}) = pc.K[2,3]
198196

199197
# set_f_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,1] = val)
200198
# set_f_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,2] = val)
201199
# set_shear!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,2] = val)
202-
# set_c_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,3] = val)
203-
# set_c_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,3] = val)
200+
# set_pp_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,3] = val)
201+
# set_pp_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,3] = val)
204202

205203

206204
export Pinhole

src/ExportAPI.jl

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@ export Ray, PixelIndex
1111
export pixel2ray, point2pixel, canreproject, sensorsize #, origin, direction,
1212
export project, projectHomogeneous
1313
export backproject, backprojectHomogeneous
14+
export pp_w, pp_h, f_w, f_h
1415

1516
export lookdirection, updirection #, columns, rows
1617

src/services/CameraServices.jl

Lines changed: 62 additions & 55 deletions
Original file line numberDiff line numberDiff line change
@@ -15,31 +15,35 @@ direction(vector::Union{<:AbstractVector{<:Real},<:Vector3}) = vector
1515
direction(ray::Ray) = ray.direction
1616
sensorsize(cameramodel::AbstractCameraModel) = SVector{2}(width(cameramodel), height(cameramodel))
1717

18-
"""
19-
canreproject(camera::CameraModel)
20-
21-
Confirms if point2pixel is implemented for this camera model.
22-
"""
23-
canreproject(camera::AbstractCameraModel) = true
24-
25-
2618
## From JuliaRobotics/Caesar.jl
2719
f_w(pc::AbstractCameraModel) = pc.K[1,1]
2820
f_h(pc::AbstractCameraModel) = pc.K[2,2]
2921
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]
22+
pp_w(pc::AbstractCameraModel) = pc.K[1,3]
23+
pp_h(pc::AbstractCameraModel) = pc.K[2,3]
3224

3325
set_f_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,1] = val)
3426
set_f_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,2] = val)
3527
set_shear!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,2] = val)
36-
set_c_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,3] = val)
37-
set_c_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,3] = val)
28+
set_pp_w!(pc::CameraCalibrationMutable, val::Real) = (pc.K[1,3] = val)
29+
set_pp_h!(pc::CameraCalibrationMutable, val::Real) = (pc.K[2,3] = val)
30+
31+
"""
32+
canreproject(camera::CameraModel)
33+
34+
Confirms if point2pixel is implemented for this camera model.
35+
"""
36+
canreproject(camera::AbstractCameraModel) = true
3837

3938

4039
## computational functions
4140

4241

42+
## =========================================================================================
43+
## FROM SCENE IN FRONT OF CAMERA TO IMAGE -- I.E. PROJECT
44+
## =========================================================================================
45+
46+
4347

4448
"""
4549
$SIGNATURES
@@ -51,23 +55,49 @@ to camera coordinates. This currently ignores any tangential
5155
distortion between the lens and the image plane.
5256
5357
Notes
54-
- `pointincamera` is camera's reference frame.
58+
- `c_P` is a point in the camera's reference frame.
5559
5660
Deprecates:
57-
- yakir12: `point2pixel`
61+
- yakir12: `point2pixel`: @deprecate point2pixel(model, pt) project(model, pt[[1;3;2]])
5862
5963
Also see: [`backproject`](@ref)
6064
"""
6165
function project(
6266
model::AbstractCameraModel,
63-
pointincamera::Union{<:AbstractVector{<:Real}, <:Point3}
67+
c_P::Union{<:AbstractVector{<:Real}, <:Point3}
6468
)
6569
#
66-
column = c_w(model) + f_w(model) * pointincamera[1] / pointincamera[3]
67-
row = c_h(model) - f_h(model) * pointincamera[2] / pointincamera[3]
70+
column = pp_w(model) + f_w(model) * c_P[1] / c_P[3]
71+
row = pp_h(model) - f_h(model) * c_P[2] / c_P[3]
6872
return PixelIndex(column, row)
6973
end
7074

75+
## From JuliaRobotics/SensorFeatureTracking.jl
76+
function project!(
77+
ret::AbstractVector{<:Real},
78+
ci::CameraCalibration, #CameraIntrinsic,
79+
ce::ArrayPartition,
80+
pt::Vector{Float64}
81+
)
82+
res = ci.K*(ce.R*pt + ce.t)
83+
ret[1:2] = res[1:2]./res[3]
84+
nothing
85+
end
86+
87+
project!(
88+
ret::AbstractVector{<:Real},
89+
cm::CameraModelFull,
90+
pt::AbstractVector{<:Real}) = project!(ret, cm.ci, cm.ce, pt)
91+
92+
function project(
93+
cm::CameraModelFull,
94+
pt::AbstractVector{<:Real}
95+
)
96+
res = Vector{Float64}(2)
97+
project!(res, cm, pt)
98+
return res
99+
end
100+
71101
## homogeneous point coords xyzw (stereo cameras)
72102
# xyzw are in the camera frame (c_), i.e. x-columns, y-rows, z-forward
73103
function projectHomogeneous(
@@ -78,21 +108,25 @@ function projectHomogeneous(
78108
x,y,z,w = (c_Ph...,)
79109
fxz = f_w(cam) / z
80110
fyz = f_h(cam) / z
81-
w = x * fxz + c_w(cam) # add center to get PixelIndex
82-
h = y * fyz + c_h(cam)
111+
col = x * fxz + pp_w(cam) # add center to get PixelIndex
112+
row = y * fyz + pp_h(cam)
113+
# infront or behind
83114
if (w==0&&0<z) || 0 < (z/w)
84-
PixelIndex(w,h)
115+
PixelIndex(col,row)
85116
else
86117
PixelIndex(0.,0.; valid=false)
87118
end
88119
end
89120
# # right cam
90121
# u2 = (x - w*baseline) * fz + center[1]
91-
# # infront or behind
92-
# valid = (w==0&&0<z) || 0 < (z/w)
93122

94123

95124

125+
## =========================================================================================
126+
## FROM IMAGE TO SCENE IN FRONT OF CAMERA -- I.E. BACKPROJECT
127+
## =========================================================================================
128+
129+
96130
"""
97131
$SIGNATURES
98132
@@ -103,7 +137,7 @@ to camera coordinates. This currently ignores any tangential
103137
distortion between the lens and the image plane.
104138
105139
Deprecates:
106-
- yakir12: `pixel2ray`
140+
- yakir12: `pixel2ray`: @deprecate pixel2ray(model, px) backproject(model, px)[[1;3;2]]
107141
108142
Also see: [`project`](@ref)
109143
"""
@@ -112,9 +146,9 @@ function backproject(
112146
px_coord::Union{<:AbstractVector{<:Real}, <:PixelIndex}
113147
)
114148
#
115-
x = (px_coord[1] - c_w(model)) / f_w(model)
116-
y = -(px_coord[2] - c_h(model)) / f_h(model)
117-
return Vector3(x, y, 1)
149+
col = (px_coord[1] - pp_w(model)) / f_w(model)
150+
row = -(px_coord[2] - pp_h(model)) / f_h(model)
151+
return Vector3(col, row, 1)
118152
end
119153
# # camera measurements (u,v), (u2,v)
120154
# lx = (u-center[1])*baseline
@@ -128,45 +162,18 @@ end
128162

129163

130164
## =========================================================================================
131-
## REFACTOR AND CONSOLIDATE BELOW
165+
## RESIDUAL FUNCTION FOR OPTIMIZATION OR LOSS
132166
## =========================================================================================
133167

134168

135-
## From JuliaRobotics/SensorFeatureTracking.jl
136-
137-
function project!(
138-
ret::AbstractVector{<:Real},
139-
ci::CameraCalibration, #CameraIntrinsic,
140-
ce::ArrayPartition,
141-
pt::Vector{Float64}
142-
)
143-
res = ci.K*(ce.R*pt + ce.t)
144-
ret[1:2] = res[1:2]./res[3]
145-
nothing
146-
end
147-
148-
project!(
149-
ret::AbstractVector{<:Real},
150-
cm::CameraModelFull,
151-
pt::AbstractVector{<:Real}) = project!(ret, cm.ci, cm.ce, pt)
152-
153-
function project(
154-
cm::CameraModelFull,
155-
pt::AbstractVector{<:Real}
156-
)
157-
res = Vector{Float64}(2)
158-
project!(res, cm, pt)
159-
return res
160-
end
161-
162169
# pinhole camera model
163170
# (x, y)/f = (X, Y)/Z
164171
function cameraResidual!(
165172
res::AbstractVector{<:Real},
166173
z::AbstractVector{<:Real},
167174
ci::CameraCalibration, #CameraIntrinsic,
168175
ce::ArrayPartition,
169-
pt::AbstractVector{<:Real}
176+
pt::Union{PixelIndex,<:AbstractVector{<:Real}},
170177
)
171178
# in place memory operations
172179
project!(res, ci, ce, pt)

0 commit comments

Comments
 (0)