Class OculusSubsystem

java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
frc.alotobots.library.subsystems.vision.oculus.OculusSubsystem
All Implemented Interfaces:
Sendable, Subsystem

public class OculusSubsystem extends SubsystemBase
Manages communication and pose estimation with a Meta Quest VR headset.

This subsystem leverages the Quest's inside-out SLAM tracking system to provide high-frequency (120Hz) robot pose estimation. Key features:

- Global SLAM-based localization - Field mapping and persistence - Sub-centimeter tracking precision - High update rate (120Hz) - Drift-free position tracking - Fast relocalization

The system operates in phases: 1. Pre-match mapping to capture field features 2. Initial pose acquisition and alignment 3. Continuous pose updates during match 4. Recovery handling if tracking is lost

  • Constructor Details

    • OculusSubsystem

      public OculusSubsystem(OculusSubsystem.OculusConsumer oculusConsumer, OculusIO io)
      Creates a new OculusSubsystem.

      Initializes communication with Quest hardware and prepares logging systems. The subsystem starts in an uninitialized state requiring pose calibration.

      Parameters:
      oculusConsumer - Consumer that receives pose updates from the headset
      io - Interface for Quest hardware communication
  • Method Details

    • periodic

      public void periodic()
      Updates subsystem state and processes Quest data.

      Called periodically by the command scheduler. This method: - Updates hardware inputs - Processes new pose data - Handles state transitions - Manages reset operations - Updates logging

    • getBatteryPercent

      public double getBatteryPercent()
      Returns the battery percentage of the connected Quest headset.
      Returns:
      Battery percentage (0-100)
    • getTimestamp

      public double getTimestamp()
      Returns the timestamp of the most recent pose update.
      Returns:
      Timestamp in seconds
    • isConnected

      public boolean isConnected()
      Checks if the Quest headset is currently connected.
      Returns:
      True if connected, false otherwise
    • getPose

      public Pose2d getPose()
      Gets the current robot pose as estimated by the Quest headset. This incorporates all transforms and offsets to convert from headset to robot coordinates.
      Returns:
      Field-relative robot pose
    • resetPose

      public void resetPose(Pose2d pose)
      Resets the pose tracking system to a specified position. Must be called only when the robot is disabled to avoid interrupting tracking during a match.
      Parameters:
      pose - The new reference pose
    • resetPose

      public void resetPose(Pose2d pose, boolean overrideEnabledCheck)
      Resets the pose tracking system to a specified position. Must be called only when the robot is disabled to avoid interrupting tracking during a match.
      Parameters:
      pose - The new reference pose
      overrideEnabledCheck - Overrides the enabled check to allow for resetting while enabled.
    • updateTransform

      public void updateTransform(Pose2d pose)
      Updates the transform offset used in ROBOT_SIDE pose reset strategy. Has no effect if using a different pose reset strategy.
      Parameters:
      pose - The new reference pose for calculating offset