Class VisOdomStereoQuadPnP<T extends ImageGray<T>,TD extends TupleDesc<TD>>

java.lang.Object
boofcv.alg.sfm.d3.VisOdomStereoQuadPnP<T,TD>
All Implemented Interfaces:
VerbosePrint

public class VisOdomStereoQuadPnP<T extends ImageGray<T>,TD extends TupleDesc<TD>> extends Object implements VerbosePrint
Stereo visual odometry algorithm which associates image features across two stereo pairs for a total of four images. Image features are first matched between left and right images while applying epipolar constraints. Then the two more recent sets of stereo images are associated with each other in a left to left and right to right fashion. Features which are consistently matched across all four images are saved in a list. RANSAC is then used to remove false positives and estimate camera motion using a PnP type algorithm. Motion is estimated using PNP with RANSAC. The initial 3D location of a feature is found using the stereo pair in the key frame. After the initial motion is found it can optionally be refined. Now that the location of all four cameras is known points are triangulated again using all four views. Then the optional final step is to run bundle adjustment. Features are uniquely tracked from one image to the next. This allows the refined 3D location of each feature to benefit future frames instead of being lost. However, due to the nature of the DDA image tracker, losing track is quite common. The previous stereo pair is referred to as the key frame because it's the reference point that motion is estimated relative to. Inside the code each camera is some times referred to by number. 0 = left camera key frame. 1 = key camera previous frame. 2 = left camera current frame. 3 = right camera current frame.
  • Field Details

    • profileOut

      @Nullable protected @Nullable PrintStream profileOut
    • verbose

      @Nullable protected @Nullable PrintStream verbose
  • Constructor Details

  • Method Details

    • setCalibration

      public void setCalibration(StereoParameters param)
      Sets and saves the stereo camera's calibration
    • reset

      public void reset()
      Resets the algorithm into its original state
    • process

      public boolean process(T left, T right)
      Estimates camera egomotion from the stereo pair
      Parameters:
      left - Image from left camera
      right - Image from right camera
      Returns:
      true if motion was estimated and false if not
    • getLeftToWorld

      public Se3_F64 getLeftToWorld()
    • setVerbose

      public void setVerbose(@Nullable @Nullable PrintStream out, @Nullable @Nullable Set<String> configuration)
      Specified by:
      setVerbose in interface VerbosePrint