symforce.cam.double_sphere_camera_cal module¶
- class DoubleSphereCameraCal(focal_length, principal_point, xi, alpha)[source]¶
Bases:
CameraCal
Camera model where a point is consecutively projected onto two unit spheres with centers shifted by
xi
, then projected into the image plane using the pinhole model shifted byalpha / (1 - alpha)
.There are important differences here from the derivation in the paper and in other open-source packages with double sphere models; see notebooks/double_sphere_derivation.ipynb for more information.
The storage for this class is:
[ fx fy cx cy xi alpha ]
TODO(aaron): Create double_sphere_derivation.ipynb
TODO(aaron): Probably want to check that values and derivatives are correct (or at least sane) on the valid side of the is_valid boundary
- Parameters:
focal_length (T.Sequence[T.Scalar]) –
principal_point (T.Sequence[T.Scalar]) –
xi (T.Scalar) –
alpha (T.Scalar) –
- NUM_DISTORTION_COEFFS = 2¶
- classmethod symbolic(name, **kwargs)[source]¶
Construct a symbolic element with the given name prefix. Kwargs are forwarded to
sf.Symbol
(for example, sympy assumptions).- Parameters:
- Return type:
- classmethod storage_order()[source]¶
Return list of the names of values returned in the storage paired with the dimension of each value.
- pixel_from_camera_point(point, epsilon=0.0)[source]¶
Project a 3D point in the camera frame into 2D pixel coordinates.