Class BundlePinholeSimplified

java.lang.Object
boofcv.alg.geo.bundle.cameras.BundlePinholeSimplified
All Implemented Interfaces:
BundleAdjustmentCamera
Direct Known Subclasses:
BundlePinholeSnavely

public class BundlePinholeSimplified extends Object implements BundleAdjustmentCamera
A pinhole camera with radial distortion that is fully described using three parameters. Focal length and two radial distortion parameters. Assumptions:
  • Zero skew
  • fx and fy is the same, e.g. square pixels
  • No tangential distortion
  • Image center is at coordinate (0,0)
The image center being at (0,0) only matters if the camera's FOV is being enforced by filtering out pixels that are outside the image. With this camera model pixels can have positive and negative values.
  • Field Details

    • TYPE_NAME

      public static final String TYPE_NAME
      See Also:
    • f

      public double f
    • k1

      public double k1
    • k2

      public double k2
  • Constructor Details

    • BundlePinholeSimplified

      public BundlePinholeSimplified()
    • BundlePinholeSimplified

      public BundlePinholeSimplified(double f, double k1, double k2)
  • Method Details

    • setIntrinsic

      public void setIntrinsic(double[] parameters, int offset)
      Description copied from interface: BundleAdjustmentCamera
      Specifies the intrinsic camera parameters.
      Specified by:
      setIntrinsic in interface BundleAdjustmentCamera
      Parameters:
      parameters - Array containing the parameters
      offset - Location of first index in the array which the parameters are stored
    • getIntrinsic

      public void getIntrinsic(double[] parameters, int offset)
      Description copied from interface: BundleAdjustmentCamera
      Copies the intrinsic camera into the array.
      Specified by:
      getIntrinsic in interface BundleAdjustmentCamera
      Parameters:
      parameters - Array containing the parameters
      offset - Location of first index in the array which the parameters are stored
    • project

      public void project(double camX, double camY, double camZ, Point2D_F64 output)
      Description copied from interface: BundleAdjustmentCamera
      Project the 3D point in the camera reference frame onto the camera's image plane.
      Specified by:
      project in interface BundleAdjustmentCamera
      Parameters:
      camX - 3D point in camera reference frame
      camY - 3D point in camera reference frame
      camZ - 3D point in camera reference frame
      output - Storage for projected point.
    • jacobian

      public void jacobian(double X, double Y, double Z, double[] inputX, double[] inputY, boolean computeIntrinsic, @Nullable @org.jetbrains.annotations.Nullable double[] calibX, @Nullable @org.jetbrains.annotations.Nullable double[] calibY)
      Description copied from interface: BundleAdjustmentCamera
      Computes the gradient for the projected pixel coordinate with partials for the input 3D point in camera reference frame and camera intrinsic parameters. [x',y'] is the projected pixel coordinate of the 3D point in camera reference frame.
      Specified by:
      jacobian in interface BundleAdjustmentCamera
      Parameters:
      X - (Input) 3D point in camera reference frame
      Y - (Input) 3D point in camera reference frame
      Z - (Input) 3D point in camera reference frame
      inputX - (Output) Partial of projected x' relative to input camera point.[@x'/@camX, @ x' / @ camY, @ x' / @ camZ] length 3
      inputY - (Output) Partial of projected y' relative to input camera point.[@y'/@camX, @ y' / @ camY, @ y' / @ camZ] length 3
      computeIntrinsic - If true the calibX and calibY is computed. Otherwise they are ignored and can be null
      calibX - (Output) Partial of projected x' relative to calibration parameters. length N
      calibY - (Output) Partial of projected y' relative to calibration parameters. length N
    • getIntrinsicCount

      public int getIntrinsicCount()
      Description copied from interface: BundleAdjustmentCamera
      Returns the number of intrinsic parameters for this model. If the camera is known then the number of parameters is zero
      Specified by:
      getIntrinsicCount in interface BundleAdjustmentCamera
      Returns:
      number of intrinsic parameters.
    • setTo

      public BundleAdjustmentCamera setTo(Map<String,Object> src)
      Description copied from interface: BundleAdjustmentCamera
      Set's the classes state to the value contained in this map. Used when deserializing.
      Specified by:
      setTo in interface BundleAdjustmentCamera
    • toMap

      public Map<String,Object> toMap()
      Description copied from interface: BundleAdjustmentCamera
      Convert's the values into a map format where each class's field has a corresponding key with the same name and primitive value or primitive array. This is used for serialization to YAML.
      Specified by:
      toMap in interface BundleAdjustmentCamera
    • toString

      public String toString()
      Overrides:
      toString in class Object
    • reset

      public void reset()
    • setTo

      public void setTo(BundlePinholeSimplified c)
    • copy

      public BundlePinholeSimplified copy()
    • isIdentical

      public boolean isIdentical(BundlePinholeSimplified c, double tol)