navlie.lib.camera.PinholeCamera¶
- class navlie.lib.camera.PinholeCamera(fu: float, fv: float, cu: float, cv: float, image_width: int, image_height: int, sigma: float, T_bc: PoseMatrix | None = None, camera_id: Any | None = None)¶
Bases:
object
Class for a pinhole camera model.
This class contains utilities for generating measurements and predicting measurements, and converting pixel coordinates to normalized image coordinates using the camera intrinsic parameters.
Instantiate a PinholeCamera
- Parameters:
fu (float) – Focal length, horizontal pixels.
fv (float) – Focal length, vertical pixels.
cu (float) – Optical axis intersection, horizontal pixels.
cv (float) – Optical axis intersection, vertical pixels.
image_width (int) – Image Plane width in pixels.
image_height (int) – Image plane height in pixels.
sigma (float) – Camera noise, in pixels.
T_bc (PoseMatrix, optional) – Transformation between the body frame and the camera frame, by default None. If None, transformation will be set to identity.
camera_id (Any, optional) – Identifier for this camera, by default None
- static get_cam_to_enu() → ndarray¶
Returns a DCM that relates the “ENU frame to the camera frame, where the camera z-axis points forward. Camera frame: x right, y down, z forward ENU frame: x forward, y left, z up
- copy() → PinholeCamera¶
Returns a copy of the camera model.
- is_measurement_valid(uv: ndarray) → bool¶
Checks if a measurement is valid.
A valid measurement should be positive and within the image plane.
- Parameters:
uv (np.ndarray) – Measurement to check.
- Returns:
Is valid.
- Return type:
- is_landmark_in_front_of_cam(pose: SE3State, r_pw_a: ndarray) → bool¶
Checks if a given landmark is in front of the camera.
- evaluate(pose: SE3State, r_pw_a: ndarray) → ndarray¶
Predicts a noise-free measurement.
- Parameters:
X (IMUState) – IMU state to generate measurement from
r_pw_a (np.ndarray) – 3D landmark position, resolved in the world frame.
- Returns:
noise-free pixel measurement
- Return type:
np.ndarray
- resolve_landmark_in_cam_frame(pose: SE3State, r_pw_a: ndarray)¶
Resolves a landmark with position r_pw_a in the camera frame.
- project(r_pc_c: ndarray) → ndarray¶
Pinhole projection model.
- Parameters:
r_pc_c (np.ndarray) – Landmark relative to camera, resolved in camera frame.
- Returns:
(u, v) pixel coordinates.
- Return type:
np.ndarray