Skip to main content

IMatcher

The IMatcher interface is responsible for estimating dense optical flow between two frames, with optional uncertainty estimation and occlusion mask prediction.

Interface

class IMatcher(ABC, Generic[T_Context], ConfigTestableSubclass):
@property
@abstractmethod
def provide_cov(self) -> bool: ...

@abstractmethod
def init_context(self) -> T_Context: ...

@abstractmethod
def forward(self, frame_t1: StereoData, frame_t2: StereoData) -> IMatcher.Output: ...

Output Structure

The interface defines an Output dataclass with the following fields:

  • flow: torch.Tensor (B×2×H×W) - Estimated optical flow map
  • cov: Optional[torch.Tensor] (B×3×H×W) - Estimated covariance of optical flow (if provided)
    • The three channels are uu, vv, and uv respectively, forming a 2×2 covariance matrix: [[uu, uv], [uv, vv]]
  • mask: Optional[torch.Tensor] (B×1×H×W) - Boolean mask indicating valid (not occluded) prediction regions

Methods to Implement

  • provide_cov -> bool

    • Property indicating whether the implementation provides covariance estimation
    • Must return True if the implementation outputs flow uncertainty
  • init_context() -> T_Context

    • Initializes model-specific context (e.g., neural networks, parameters)
    • Called during initialization
    • Access configuration via self.config
  • forward(frame_t1: StereoData, frame_t2: StereoData) -> IMatcher.Output

    • Core method for flow estimation
    • Input frames contain stereo image pairs (imageL, imageR) of shape B×3×H×W
    • Returns IMatcher.Output with flow and optional covariance/mask
    • May pad outputs with nan if prediction shape differs from input

Implementations

Base Models

  • GTMatcher

    • Returns ground truth optical flow from dataset
    • Raises AssertionError if ground truth not available
    • Does not provide covariance estimation
  • FlowFormerMatcher

    • Uses vanilla FlowFormer model for flow estimation
    • Does not provide covariance estimation
    • Configuration:
      • weight: Path to model weights
      • device: Target device ("cuda" or "cpu")
  • FlowFormerCovMatcher

    • Modified FlowFormer with joint flow and uncertainty estimation
    • Provides covariance estimation
    • Same configuration as FlowFormerMatcher
  • TartanVOMatcher

    • Uses TartanVO frontend for flow estimation
    • Does not provide covariance estimation
    • Pads output with nan if shape not multiple of 64
    • Configuration:
      • weight: Path to model weights
      • device: Target device ("cuda" or "cpu")
  • TartanVOCovMatcher

    • Modified TartanVO with joint flow and uncertainty estimation
    • Provides covariance estimation
    • Same configuration as TartanVOMatcher

Modifiers

  • ApplyGTMatchCov
    • Higher-order module that wraps another IMatcher
    • Compares estimated flow with ground truth to generate covariance
    • Requires ground truth flow data
    • Generates diagonal covariance matrix only
    • Configuration:
      • module: Configuration for wrapped matcher

Usage in MAC-VO

The IMatcher interface is primarily used in:

  1. Frontend processing for visual odometry
  2. Flow evaluation and benchmarking
  3. Visualization and debugging

Example usage:

matcher = IMatcher.instantiate(config.match.type, config.match.args)
flow_output = matcher.estimate(frame_t1.stereo, frame_t2.stereo)

# Access results
flow = flow_output.flow # B×2×H×W tensor
cov = flow_output.cov # B×3×H×W tensor or None
mask = flow_output.mask # B×1×H×W tensor or None