navlie

  • Home
  • Tutorial
  • API
  • navlie.composite
    • navlie.composite.CompositeInput
    • navlie.composite.CompositeMeasurement
    • navlie.composite.CompositeMeasurementModel
    • navlie.composite.CompositeProcessModel
    • navlie.composite.CompositeState
  • navlie.datagen
    • navlie.datagen.generate_measurement
    • navlie.datagen.DataGenerator
  • navlie.filters
    • navlie.filters.check_outlier
    • navlie.filters.generate_sigmapoints
    • navlie.filters.mean_state
    • navlie.filters.run_filter
    • navlie.filters.run_gsf_filter
    • navlie.filters.run_imm_filter
    • navlie.filters.CubatureKalmanFilter
    • navlie.filters.ExtendedKalmanFilter
    • navlie.filters.GaussHermiteKalmanFilter
    • navlie.filters.GaussianSumFilter
    • navlie.filters.InteractingModelFilter
    • navlie.filters.IteratedKalmanFilter
    • navlie.filters.SigmaPointKalmanFilter
    • navlie.filters.UnscentedKalmanFilter
  • navlie.types
    • navlie.types.Dataset
    • navlie.types.Input
    • navlie.types.Measurement
    • navlie.types.MeasurementModel
    • navlie.types.ProcessModel
    • navlie.types.State
    • navlie.types.StateWithCovariance
  • navlie.utils
    • navlie.utils.alignment
      • navlie.utils.alignment.associate_and_align_trajectories
      • navlie.utils.alignment.evo_traj_to_state_list
      • navlie.utils.alignment.state_list_to_evo_traj
    • navlie.utils.common
      • navlie.utils.common.associate_stamps
      • navlie.utils.common.find_nearest_stamp_idx
      • navlie.utils.common.jacobian
      • navlie.utils.common.load_tum_trajectory
      • navlie.utils.common.monte_carlo
      • navlie.utils.common.randvec
      • navlie.utils.common.schedule_sequential_measurements
      • navlie.utils.common.state_interp
      • navlie.utils.common.van_loans
      • navlie.utils.common.GaussianResult
      • navlie.utils.common.GaussianResultList
      • navlie.utils.common.MixtureResult
      • navlie.utils.common.MixtureResultList
      • navlie.utils.common.MonteCarloResult
    • navlie.utils.mixture
      • navlie.utils.mixture.gaussian_mixing
      • navlie.utils.mixture.gaussian_mixing_vectorspace
      • navlie.utils.mixture.reparametrize_gaussians_about_X_par
      • navlie.utils.mixture.update_X
    • navlie.utils.plot
      • navlie.utils.plot.plot_camera_poses
      • navlie.utils.plot.plot_error
      • navlie.utils.plot.plot_meas
      • navlie.utils.plot.plot_meas_by_model
      • navlie.utils.plot.plot_nees
      • navlie.utils.plot.plot_poses
      • navlie.utils.plot.set_axes_equal
      • navlie.utils.plot.CameraPoseVisualizer
  • navlie.batch
    • navlie.batch.estimator
      • navlie.batch.estimator.BatchEstimator
    • navlie.batch.gaussian_mixtures
      • navlie.batch.gaussian_mixtures.GaussianMixtureResidual
      • navlie.batch.gaussian_mixtures.HessianSumMixtureResidual
      • navlie.batch.gaussian_mixtures.MaxMixtureResidual
      • navlie.batch.gaussian_mixtures.MaxSumMixtureResidual
      • navlie.batch.gaussian_mixtures.SumMixtureResidual
    • navlie.batch.losses
      • navlie.batch.losses.CauchyLoss
      • navlie.batch.losses.L2Loss
      • navlie.batch.losses.LossFunction
    • navlie.batch.problem
      • navlie.batch.problem.OptimizationSummary
      • navlie.batch.problem.Problem
    • navlie.batch.residuals
      • navlie.batch.residuals.MeasurementResidual
      • navlie.batch.residuals.PriorResidual
      • navlie.batch.residuals.ProcessResidual
      • navlie.batch.residuals.Residual
  • navlie.lib
    • navlie.lib.camera
      • navlie.lib.camera.PinholeCamera
      • navlie.lib.camera.PoseMatrix
    • navlie.lib.datasets
      • navlie.lib.datasets.generate_landmark_positions
      • navlie.lib.datasets.SimulatedInertialGPSDataset
      • navlie.lib.datasets.SimulatedInertialLandmarkDataset
      • navlie.lib.datasets.SimulatedPoseRangingDataset
    • navlie.lib.imu
      • navlie.lib.imu.G_matrix
      • navlie.lib.imu.G_matrix_inv
      • navlie.lib.imu.L_matrix
      • navlie.lib.imu.M_matrix
      • navlie.lib.imu.N_matrix
      • navlie.lib.imu.U_matrix
      • navlie.lib.imu.U_matrix_inv
      • navlie.lib.imu.U_tilde_matrix
      • navlie.lib.imu.adjoint_IE3
      • navlie.lib.imu.delta_matrix
      • navlie.lib.imu.get_unbiased_imu
      • navlie.lib.imu.inverse_IE3
      • navlie.lib.imu.IMU
      • navlie.lib.imu.IMUKinematics
      • navlie.lib.imu.IMUState
    • navlie.lib.models
      • navlie.lib.models.AbsolutePosition
      • navlie.lib.models.AbsoluteVelocity
      • navlie.lib.models.Altitude
      • navlie.lib.models.BodyFrameVelocity
      • navlie.lib.models.CameraProjection
      • navlie.lib.models.DoubleIntegrator
      • navlie.lib.models.DoubleIntegratorWithBias
      • navlie.lib.models.GlobalPosition
      • navlie.lib.models.Gravitometer
      • navlie.lib.models.InvariantMeasurement
      • navlie.lib.models.InvariantPointRelativePosition
      • navlie.lib.models.LinearMeasurement
      • navlie.lib.models.Magnetometer
      • navlie.lib.models.OneDimensionalPositionVelocityRange
      • navlie.lib.models.PointRelativePosition
      • navlie.lib.models.PointRelativePositionSLAM
      • navlie.lib.models.RangePointToAnchor
      • navlie.lib.models.RangePoseToAnchor
      • navlie.lib.models.RangePoseToPose
      • navlie.lib.models.RangeRelativePose
      • navlie.lib.models.RelativeBodyFrameVelocity
      • navlie.lib.models.SingleIntegrator
    • navlie.lib.preintegration
      • navlie.lib.preintegration.AngularVelocityIncrement
      • navlie.lib.preintegration.BodyVelocityIncrement
      • navlie.lib.preintegration.IMUIncrement
      • navlie.lib.preintegration.LinearIncrement
      • navlie.lib.preintegration.PreintegratedAngularVelocity
      • navlie.lib.preintegration.PreintegratedBodyVelocity
      • navlie.lib.preintegration.PreintegratedIMUKinematics
      • navlie.lib.preintegration.PreintegratedLinearModel
      • navlie.lib.preintegration.PreintegratedWheelOdometry
      • navlie.lib.preintegration.RelativeMotionIncrement
      • navlie.lib.preintegration.WheelOdometryIncrement
    • navlie.lib.states
      • navlie.lib.states.MatrixLieGroupState
      • navlie.lib.states.MixtureState
      • navlie.lib.states.SE23State
      • navlie.lib.states.SE2State
      • navlie.lib.states.SE3State
      • navlie.lib.states.SL3State
      • navlie.lib.states.SO2State
      • navlie.lib.states.SO3State
      • navlie.lib.states.StampedValue
      • navlie.lib.states.VectorInput
      • navlie.lib.states.VectorState
  • navlie.bspline
    • navlie.bspline.SE3Bspline
On this page
  • PinholeCamera
    • PinholeCamera.get_cam_to_enu()
    • PinholeCamera.intrinsics
    • PinholeCamera.sigma_normalized_image_coords
    • PinholeCamera.R_normalized_image_coords
    • PinholeCamera.copy()
    • PinholeCamera.is_measurement_valid()
    • PinholeCamera.is_landmark_in_front_of_cam()
    • PinholeCamera.evaluate()
    • PinholeCamera.resolve_landmark_in_cam_frame()
    • PinholeCamera.project()
    • PinholeCamera.to_normalized_coords()
    • PinholeCamera.to_pixel_coors()

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

property intrinsics: ndarray¶

Returns the intrinsic matrix K.

property sigma_normalized_image_coords: ndarray¶
property R_normalized_image_coords: ndarray¶
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:

bool

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

to_normalized_coords(uv: ndarray) → ndarray¶

Converts (u, v) pixel coordinates to normalized image coordinates.

Parameters:

uv (np.ndarray) – Pixel coordinates

Returns:

Normalized image coordinates, computed using intrinsics.

Return type:

np.ndarray

to_pixel_coors(meas: ndarray) → ndarray¶

previous

navlie.lib.camera

next

navlie.lib.camera.PoseMatrix

© Copyright 2022.

Created using Sphinx 7.1.2.