All Known Implementing Classes:
AprilTagPoseSource, AprilTagSubsystem, OculusPoseSource, OculusSubsystem

public interface PoseSource
Standardized interface for pose estimation sources in the robot localization system.

This interface defines the contract that all pose sources must fulfill to integrate with the localization fusion system. It supports various types of pose sources including:

- Meta Quest SLAM (primary source) - AprilTag vision (secondary source) - Wheel odometry (emergency backup) - Other potential sources (e.g., LiDAR, external cameras)

Each source must provide: - Connection status monitoring - Current pose estimation - Measurement uncertainty estimates - Source identification

  • Method Summary

    Modifier and Type
    Method
    Description
    Gets the most recent pose estimate from this source.
    Gets a human-readable identifier for this pose source.
    Gets the standard deviations of measurement uncertainty for this pose source.
    boolean
    Checks if the pose source is currently connected and providing valid data.
  • Method Details

    • isConnected

      boolean isConnected()
      Checks if the pose source is currently connected and providing valid data.

      This method should: - Verify hardware connectivity (if applicable) - Check data freshness - Validate sensor readings - Monitor update frequency

      Returns:
      true if the source is connected and providing valid data
    • getCurrentPose

      Pose2d getCurrentPose()
      Gets the most recent pose estimate from this source.

      The returned pose should be: - In field-relative coordinates - Using the standard FRC coordinate system: - Origin at field corner - +X towards opposite alliance wall - +Y towards driver station - CCW positive rotation

      If no valid pose is available, returns null.

      Returns:
      The current robot pose estimate, or null if unavailable
    • getStdDevs

      Matrix<N3,N1> getStdDevs()
      Gets the standard deviations of measurement uncertainty for this pose source.

      Returns a 3x1 matrix containing standard deviations for: - X position (meters) - Y position (meters) - Rotation (radians)

      These values should: - Reflect real measurement uncertainty - Scale with distance/conditions - Account for systematic errors - Consider environmental factors

      Returns:
      3x1 matrix of standard deviations [x, y, theta]
    • getSourceName

      String getSourceName()
      Gets a human-readable identifier for this pose source.

      Used for: - Logging - Debugging - User interfaces - Status reporting

      Returns:
      String identifier for this pose source