Class VisOdomDualTrackPnP<T extends ImageBase<T>,TD extends TupleDesc<TD>>

All Implemented Interfaces:
VerbosePrint

public class VisOdomDualTrackPnP<T extends ImageBase<T>,TD extends TupleDesc<TD>> extends VisOdomBundlePnPBase<VisOdomDualTrackPnP.TrackInfo>
Stereo visual odometry algorithm which relies on tracking features independently in the left and right images and then matching those tracks together. The idea behind this tracker is that the expensive task of association features between left and right cameras only needs to be done once when track is spawned. Triangulation is used to estimate each feature's 3D location. Motion is estimated robustly using a RANSAC type algorithm provided by the user which internally uses PnP type algorithm. Estimated motion is relative to left camera. FUTURE WORK: Save visual tracks without stereo matches and do monocular tracking on them. This is useful for stereo systems with only a little bit of overlap.
  • Field Details

  • Constructor Details

    • VisOdomDualTrackPnP

      public VisOdomDualTrackPnP(double epilolarTol, PointTracker<T> trackerLeft, PointTracker<T> trackerRight, DescribePointRadiusAngle<T,TD> describe, AssociateDescription2D<TD> assocL2R, Triangulate2ViewsMetric triangulate2, ModelMatcher<Se3_F64,Stereo2D3D> matcher, @Nullable @Nullable ModelFitter<Se3_F64,Stereo2D3D> modelRefiner)
      Specifies internal algorithms and parameters
      Parameters:
      epilolarTol - Tolerance in pixels for enforcing the epipolar constraint
      trackerLeft - Tracker used for left camera
      trackerRight - Tracker used for right camera
      describe - Describes features in tracks
      assocL2R - Assocation for left to right
      triangulate2 - Triangulation for estimating 3D location from stereo pair
      matcher - Robust motion model estimation with outlier rejection
      modelRefiner - Non-linear refinement of motion model
  • Method Details

    • setCalibration

      public void setCalibration(StereoParameters param)
      Specifies the stereo parameters. Note that classes which are passed into constructor are maintained outside. Example, the RANSAC distance model might need to have stereo parameters passed to it externally since there's no generic way to handle that.
    • reset

      public void reset()
      Resets the algorithm into its original state
      Overrides:
      reset in class VisOdomBundlePnPBase<VisOdomDualTrackPnP.TrackInfo>
    • process

      public boolean process(T left, T right)
      Updates motion estimate using the stereo pair.
      Parameters:
      left - Image from left camera
      right - Image from right camera
      Returns:
      true if motion estimate was updated and false if not
    • getFrameID

      public long getFrameID()
      Specified by:
      getFrameID in class VisOdomBundlePnPBase<VisOdomDualTrackPnP.TrackInfo>
    • isFault

      public boolean isFault()
      If there are no candidates then a fault happened.
      Returns:
      true if fault. false is no fault
    • dropVisualTrack

      protected void dropVisualTrack(PointTrack left)
      Description copied from class: VisOdomBundlePnPBase
      Given the BTrack drop all visual tracks which belong to it.
      Specified by:
      dropVisualTrack in class VisOdomBundlePnPBase<VisOdomDualTrackPnP.TrackInfo>