CatadioptricCamera#
- class CatadioptricCamera(k: float | None = None, projection: str = 'equiangular', maxangle: float | None = None, **kwargs)[source]#
Create catadioptric camera projection model

- Parameters:
k (float, optional) – scale factor
projection (str, optional) – projection model:
'equiangular'[default],'sine','equisolid'or'stereographic'kwargs – arguments passed to
CameraBaseconstructor
A catadioptric camera comprises a perspective camera pointed at a convex mirror, typically paraboloidal or conical.
The elevation angle range is from \(-\pi/2\) (below the mirror) to maxangle above the horizontal plane. The mapping from elevation angle \(\theta\) to image plane radius is given by:
Projection
\(r(\theta)\)
equiangular
\(r = k \theta\)
sine
\(r = k \sin \theta\)
equisolid
\(r = k \sin \frac{\theta}{2}\)
stereographic
\(r = k \tan \frac{\theta}{2}\)
Note
If
Kis not specified it is computed such that the circular imaging region maximally fills the image plane.This camera model assumes central projection, that is, the focal point is at \(z=0\) and the image plane is at \(z=f\). The image is not inverted.
- References:
P. Corke, Robotics, Vision & Control for Python, Springer, 2023, Section 13.3.2.
- Seealso:
CameraBaseCentralCameraFishEyeCameraSphericalCamera
Methods
Clear the virtual image plane (base method)
Display image on virtual image plane (base method)
Move camera (base method)
Plot 3D camera icon in world view (base method)
Plot 2D line on virtual image plane (base method)
Plot points on virtual image plane (base method)
Plot 3D wireframe in virtual image plane (base method)
Project 3D points to image plane
Reset camera pose (base method)
Attributes
Set/get camera type (base method)
Set/Get distortion model (base method)
Get image plane height (base method)
Set/get size of virtual image plane (base method)
Set/get camera name (base method)
Set/Get projection noise (base method)
Get image plane width (base method)
Get image plane height (base method)
Set/get camera pose (base method)
Set/get principal point coordinate (base method)
Get pixel dimensions (base method)
Get pixel width (base method)
Get pixel width (base method)
Get principal point: horizontal coordinate (base method)
Get principal point: vertical coordinate (base method)
Get image plane width (base method)