Projections
Camera and orthographic projections — 3D → 2D
class ProjectionModel Enum
Supported camera projection models.
Each member represents a complete 3D → 2D projection function, covering
both the ideal projection geometry and its associated distortion model.
Models
- Pinhole: Ideal perspective projection, no distortion. Parameters: fx, fy, cx, cy.
- BrownConrady: Pinhole + radial/tangential distortion. D = (k1, k2, p1, p2, k3). OpenCV default, ROS `
plumb_bob`. - KannalaBrandt: Fisheye / equidistant. D = (k1, k2, k3, k4). `
cv2.fisheye, ROSkannala_brandt`. - Division: Simple wide-angle with single division coefficient. D = (k1,).
- Rational: Full rational polynomial. D = (k1, k2, p1, p2, k3, k4, k5, k6). ROS `
rational_polynomial`. - Fisheye62: Project Aria fisheye model. D = (k0, k1, k2, k3, p0, p1).
- MeiUnified: Unified omnidirectional camera model (Mei 2007). D = (xi, k1, k2). Used by KITTI-360 fisheye cameras.
Members
| Name | Value |
|---|---|
Pinhole | — |
BrownConrady | — |
KannalaBrandt | — |
Division | — |
Rational | — |
Fisheye62 | — |
MeiUnified | — |
Methods
ProjectionModel.from_stringfrom_string(cls, model_str: str) -> ProjectionModel
Convert a string to a ProjectionModel enum value.
Accepts ROS `distortion_model` names and legacy tgraph names.
class Projection(BaseTransform)
A 3D to 2D projection transformation.
Stores a projection matrix P that maps 3D homogeneous points to 2D.
Internally stored as 4x4 matrix with bottom row [0, 0, 0, 1] for compatibility.
The project_points() method projects 3D points to 2D pixel coordinates.
Note: Projections are generally non-invertible. The inverse() method returns
an InverseProjection which represents the conceptual inverse but requires
additional depth information to actually unproject points.
Constructors
Projection.__init____init__( self, matrix: np.ndarray | list, dtype: np.dtype = <class 'np.float64'> )
Create a Projection from a 3x4 or 4x4 matrix.
Parameters
- matrix
- 3x4 or 4x4 projection matrix.
- dtype
- Data type for the matrix.
Projection.from_dictfrom_dict(cls, data: dict[str, Any]) -> Projection
Deserialize projection from a dictionary.
Methods
Projection.as_matrixas_matrix(self) -> np.ndarray
Returns the 4x4 projection matrix.
Projection.as_matrix_3x4as_matrix_3x4(self) -> np.ndarray
Returns the 3x4 projection matrix (top 3 rows).
Projection.inverseinverse(self) -> InverseProjection
Returns an InverseProjection representing P^-1.
Note: The inverse projection requires depth information to actually
unproject 2D points to 3D.
Projection.project_pointsproject_points(self, points: np.ndarray | list | tuple) -> np.ndarray
Project 3D points (Nx3 or Nx4) to 2D pixel coordinates. alias for _apply(points).
Parameters
- points
- Nx3 or Nx4 array of points.
Returns
np.ndarray: Nx2 pixel coordinates.
Projection.to_dictto_dict(self) -> dict[str, Any]
Serialize projection to a JSON-compatible dictionary.
class InverseProjection(BaseTransform) extends BaseTransform
Represents the conceptual inverse of a Projection (P^-1).
This class tracks that an inverse operation was requested, but actual
unprojection requires depth information. Use unproject() with depth values
to convert 2D pixels back to 3D points.
Useful for:
- Tracking transform logic in a graph
- Composing with other transforms
- Unprojecting when depth is available
Properties
original_matrix- The original projection matrix that was inverted.
Constructors
InverseProjection.from_dictfrom_dict(cls, data: dict[str, Any]) -> InverseProjection
Deserialize inverse projection from a dictionary.
Methods
InverseProjection.as_matrixas_matrix(self) -> np.ndarray
Returns a pseudo-inverse matrix for composition purposes.
Warning: This is the Moore-Penrose pseudo-inverse and may not
produce geometrically meaningful results for all operations.
InverseProjection.inverseinverse(self) -> Projection
Returns the original Projection.
InverseProjection.unprojectunproject(self, pixels: np.ndarray, depths: np.ndarray) -> np.ndarray
Unproject 2D pixels to 3D points using depth values.
Parameters
- pixels
- Nx2 array of 2D pixel coordinates.
- depths
- N array of depth values (Z coordinate in camera frame).
Returns
np.ndarray: Nx3 array of 3D points. Note: This assumes a standard pinhole camera model where the projection matrix can be decomposed into K[R|t] form.
InverseProjection.to_dictto_dict(self) -> dict[str, Any]
Serialize inverse projection to a JSON-compatible dictionary.
class CameraProjection(Projection)
A camera projection with strict Intrinsic-only parameters.
Adheres to the architectural guideline that CameraProjection represents
the internal geometry of the optical sensor (K, D) ONLY.
Spatial pose (Extrinsics) must be managed via separate Transform objects.
Structure:
- K: 3x3 intrinsic matrix (focal length, principal point)
- D: Distortion coefficients (OpenCV convention)
Can be constructed from:
- Explicit K parameters (with optional distortion)
- Flexible aliases: K/intrinsic_matrix, D/dist_coeffs
Properties
intrinsic_matrix- The 3x3 camera intrinsic matrix K.
fx- Focal length x.
fy- Focal length y.
cx- Principal point x.
cy- Principal point y.
focal_length- Focal lengths (fx, fy) from the intrinsic matrix.
principal_point- Principal point (cx, cy) from the intrinsic matrix.
dist_coeffs- Distortion coefficients (OpenCV ordering: k1, k2, p1, p2, k3, ...).
distortion_coefficients- Alias for dist_coeffs.
projection_model- The camera projection model (PINHOLE, BROWN_CONRADY, KANNALA_BRANDT, etc.).
image_size- Image dimensions (width, height) in pixels, if specified.
K- Alias for intrinsic_matrix (OpenCV-style).
D- Alias for dist_coeffs (OpenCV-style).
Constructors
CameraProjection.__init____init__( self, intrinsic_matrix: np.ndarray | list | None = None, dist_coeffs: list | np.ndarray | None = None, projection_model: ProjectionModel | str | None = None, image_size: tuple[int, int] | None = None, dtype: np.dtype = <class 'np.float64'>, K: np.ndarray | list | None = None, D: list | np.ndarray | None = None )
Create a CameraProjection (Intrinsic-only).
Parameters
- intrinsic_matrix
- 3x3 camera intrinsic matrix K.
- dist_coeffs
- Distortion coefficients (OpenCV ordering: k1,k2,p1,p2,k3,...).
- projection_model
- Camera model (PINHOLE, BROWN_CONRADY, KANNALA_BRANDT, etc.).
- image_size
- Image dimensions (width, height) in pixels.
- dtype
- Data type for matrices.
- K
- Alias for intrinsic_matrix.
- D
- Alias for dist_coeffs.
CameraProjection.from_intrinsics_and_transformfrom_intrinsics_and_transform(cls, *args, **kwargs)
Disabled — CameraProjection is intrinsic-only. Use separate Transform objects.
CameraProjection.from_dictfrom_dict(cls, data: dict[str, Any]) -> CameraProjection
Deserialize camera projection from a dictionary.
Methods
CameraProjection.to_dictto_dict(self) -> dict[str, Any]
Serialize camera projection to a JSON-compatible dictionary.
CameraProjection.inverseinverse(self) -> InverseCameraProjection
Returns an InverseCameraProjection for unprojection.
Preserves the camera parameters (intrinsics) in the inverse object.
class InverseCameraProjection(InverseProjection) extends InverseProjection
The inverse of a CameraProjection.
Preserves the internal CameraProjection instance to maintain access to
intrinsics (K) and distortion coefficients.
Properties
camera_projection- The original CameraProjection instance.
fx- Focal length in x from the original CameraProjection.
fy- Focal length in y from the original CameraProjection.
cx- Principal point x from the original CameraProjection.
cy- Principal point y from the original CameraProjection.
intrinsic_matrix- The 3x3 intrinsic matrix K from the original CameraProjection.
original_matrix- The original projection matrix that was inverted.
Constructors
InverseCameraProjection.from_dictfrom_dict( cls, data: dict[str, Any] ) -> InverseCameraProjection
Deserialize from dictionary.
Methods
InverseCameraProjection.inverseinverse(self) -> CameraProjection
Returns the original CameraProjection.
InverseCameraProjection.to_dictto_dict(self) -> dict[str, Any]
Serialize to dictionary using the contained CameraProjection.
class OrthographicProjection(Projection)
Orthographic (parallel) projection — maps 3D to 2D without perspective.
Unlike perspective `CameraProjection`, this applies a pure affine
mapping: the output pixel coordinates are a linear function of the input
3D coordinates, with no division by depth.
Axis conventions (default `"top"` / BEV):
* **+x** (forward) → image **top** (smaller row)
* **+y** (left) → image **left** (smaller col)
Supported axis presets:
* `"top"` — Bird's-eye view (drops Z)
* `"front"` — Front view (drops X)
* `"side"` — Side view (drops Y)
Usage::
ortho = OrthographicProjection("top", (-50, 50), (-50, 50), 0.1)
graph.add_transform("ego", "bev", ortho)
pixels = transform_points(pts, graph, "lidar", "bev")
Parameters
- axis
- Projection axis preset (`
"top","front","side"`). - u_range
- World-coordinate extent along the column axis (metres).
- v_range
- World-coordinate extent along the row axis (metres).
- resolution
- Metres per pixel.
- dtype
- Numeric data type.
Properties
axis- Projection axis preset.
u_range- World-coordinate extent along the column axis (metres).
v_range- World-coordinate extent along the row axis (metres).
resolution- Metres per pixel.
grid_shape- Output image dimensions `
(H, W)` in pixels. origin_pixel- Pixel coordinates `
(col, row)of the world origin(0, 0, 0)`.
Constructors
OrthographicProjection.__init____init__( self, axis: str = 'top', u_range: tuple[float, float] = (-50.0, 50.0), v_range: tuple[float, float] = (-50.0, 50.0), resolution: float = 0.1, dtype: np.dtype = <class 'np.float64'> )
Create a Projection from a 3x4 or 4x4 matrix.
Parameters
- matrix
- 3x4 or 4x4 projection matrix.
- dtype
- Data type for the matrix.
OrthographicProjection.from_dictfrom_dict( cls, data: dict[str, Any] ) -> OrthographicProjection
Deserialize from a dictionary.
Methods
OrthographicProjection.project_pointsproject_points(self, points: np.ndarray | list | tuple) -> np.ndarray
Alias for :meth:_apply.
OrthographicProjection.inverseinverse(self) -> InverseOrthographicProjection
Return the inverse projection.
The inverse lifts 2D pixel coordinates back to 3D, placing them on the
projection plane (the collapsed axis coordinate is set to 0).
OrthographicProjection.to_dictto_dict(self) -> dict[str, Any]
Serialize to a JSON-compatible dictionary.
class InverseOrthographicProjection(InverseProjection) extends InverseProjection
Inverse of an :class:OrthographicProjection.
Lifts 2D pixel coordinates back to 3D by inverting the affine mapping.
The collapsed axis coordinate is set to 0 (i.e. the point is placed on
the projection plane).
Properties
orthographic_projection- The original OrthographicProjection.
original_matrix- The original projection matrix that was inverted.
Constructors
InverseOrthographicProjection.from_dictfrom_dict( cls, data: dict[str, Any] ) -> InverseOrthographicProjection
Deserialize from a dictionary produced by to_dict.
Methods
InverseOrthographicProjection.inverseinverse(self) -> OrthographicProjection
Return the original OrthographicProjection.
InverseOrthographicProjection.to_dictto_dict(self) -> dict[str, Any]
Serialize to a JSON-compatible dictionary.
class CompositeProjection(Projection)
Represents a composition of a Projection (Intrinsics) and a Transform (Extrinsics).
Equivalent to: Projection * Transform
P_composite = K * T
Projects from the source frame of T directly to 2D.
Structure:
- projection: The Projection component (applied last/leftmost)
- transform: The Transform component (applied first/rightmost)
Properties
projection- The intrinsic Projection component (applied last in the chain).
transform- The extrinsic Transform component (applied first in the chain).
Constructors
CompositeProjection.__init____init__( self, projection: Projection, transform: Transform, dtype: np.dtype = <class 'np.float64'> )
Create a Projection from a 3x4 or 4x4 matrix.
Parameters
- matrix
- 3x4 or 4x4 projection matrix.
- dtype
- Data type for the matrix.
CompositeProjection.from_dictfrom_dict(cls, data: dict[str, Any]) -> CompositeProjection
Deserialize CompositeProjection from dictionary.
Methods
CompositeProjection.inverseinverse(self) -> InverseCompositeProjection
Return the inverse as an InverseCompositeProjection (T_inv * K_inv).
CompositeProjection.to_dictto_dict(self) -> dict[str, Any]
Serialize CompositeProjection (projection + transform) to dictionary.
class InverseCompositeProjection(InverseProjection) extends InverseProjection
Represents the inverse of a CompositeProjection.
Equivalent to: Transform * InverseProjection
P_inv_composite = T * K_inv
Unprojects from 2D to the source frame of T.
Structure:
- transform: The Transform component (applied last/leftmost)
- projection: The InverseProjection component (applied first/rightmost)
Properties
transform- The extrinsic Transform component (applied first in the chain).
projection- The inverse Projection component (applied last in the chain).
original_matrix- The original projection matrix that was inverted.
Constructors
InverseCompositeProjection.from_dictfrom_dict( cls, data: dict[str, Any] ) -> InverseCompositeProjection
Deserialize InverseCompositeProjection from dictionary.
Methods
InverseCompositeProjection.as_matrixas_matrix(self) -> np.ndarray
Return the combined T * K_inv matrix.
InverseCompositeProjection.inverseinverse(self) -> CompositeProjection
Return the inverse as a CompositeProjection (K * T_inv).
InverseCompositeProjection.to_dictto_dict(self) -> dict[str, Any]
Serialize InverseCompositeProjection to dictionary.