Class RobotEnvironment

java.lang.Object
frc.robot.shared.config.RobotEnvironment

public final class RobotEnvironment extends Object
Single source of truth for robot environment state: FMS attachment, simulation detection, alliance info, and Driver Station reporting.

All code outside of Robot.java should call these methods instead of reaching directly into DriverStation or RobotBase. This keeps external static dependencies in one place and allows future gating or caching logic to be applied uniformly.

  • Method Summary

    Modifier and Type
    Method
    Description
    static Optional<edu.wpi.first.wpilibj.DriverStation.Alliance>
    Returns the current alliance color, resolved from the FMS or dashboard override.
    Returns the driver station position number (1, 2, or 3).
    static double
    Returns the approximate match time remaining in the current period in seconds.
    static void
    Initializes the alliance dashboard chooser with Auto and alliance/station options.
    static boolean
    Reports whether the robot is currently in autonomous mode.
    static boolean
    Reports whether the robot is currently disabled.
    static boolean
    Reports whether the robot is currently attached to the FMS.
    static boolean
    Reports whether the code is running on real robot hardware.
    static boolean
    Reports whether the code is running in WPILib simulation.
    static boolean
    Reports whether the robot is currently in teleop mode.
    static void
    Refreshes cached environment state once per robot loop.
    static void
    reportError(String message, StackTraceElement[] stackTrace)
    Reports a fatal or high-severity error to the Driver Station console.
    static void
    reportWarning(String message, boolean printStackTrace)
    Reports a recoverable warning to the Driver Station console.
    static void
    Silences the joystick connection warning that fires in simulation when no controllers are plugged in.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Method Details

    • refreshCycle

      public static void refreshCycle()
      Refreshes cached environment state once per robot loop.

      Call this at the top of robotPeriodic() so every subsequent call in the same cycle uses the same snapshot without re-querying DriverStation.

    • isFMSAttached

      public static boolean isFMSAttached()
      Reports whether the robot is currently attached to the FMS.

      Returns the per-cycle cached value set by refreshCycle().

      Returns:
      true when connected to the official field management system
    • isSimulation

      public static boolean isSimulation()
      Reports whether the code is running in WPILib simulation.
      Returns:
      true when running in simulation rather than on a real robot
    • isReal

      public static boolean isReal()
      Reports whether the code is running on real robot hardware.
      Returns:
      true when running on a real robot
    • getAlliance

      public static Optional<edu.wpi.first.wpilibj.DriverStation.Alliance> getAlliance()
      Returns the current alliance color, resolved from the FMS or dashboard override.

      When the FMS is attached its alliance always wins. When the FMS is absent the dashboard Alliance Chooser is consulted: selecting "Blue" or "Red" forces that alliance, while "Auto (FMS)" falls through to DriverStation.getAlliance(). The resolved value is cached per cycle by refreshCycle() so all consumers in the same loop see a consistent answer.

      Returns:
      optional alliance color
    • initAllianceChooser

      public static void initAllianceChooser()
      Initializes the alliance dashboard chooser with Auto and alliance/station options.

      Call this once during RobotContainer construction. The chooser is automatically published to SmartDashboard/Alliance by the LoggedDashboardChooser constructor.

    • getLocation

      public static OptionalInt getLocation()
      Returns the driver station position number (1, 2, or 3).

      When the FMS is attached the value comes directly from the Driver Station. When the FMS is absent the dashboard alliance chooser is consulted. The resolved value is cached per cycle by refreshCycle().

      Returns:
      optional station number
    • isAutonomous

      public static boolean isAutonomous()
      Reports whether the robot is currently in autonomous mode.

      Returns the per-cycle cached value set by refreshCycle().

      Returns:
      true when the robot is running an autonomous period
    • isTeleop

      public static boolean isTeleop()
      Reports whether the robot is currently in teleop mode.

      Returns the per-cycle cached value set by refreshCycle().

      Returns:
      true when the robot is in operator-controlled teleop
    • isDisabled

      public static boolean isDisabled()
      Reports whether the robot is currently disabled.

      Returns the per-cycle cached value set by refreshCycle().

      Returns:
      true when the robot is disabled
    • getMatchTimeSeconds

      public static double getMatchTimeSeconds()
      Returns the approximate match time remaining in the current period in seconds.

      Returns the per-cycle cached value set by refreshCycle(). The value is -1.0 when no match time is available (e.g., during practice or when the FMS is not connected). During a real match, this counts down from the period length toward zero.

      Returns:
      match time remaining in seconds, or -1.0 when unavailable
    • reportError

      public static void reportError(String message, StackTraceElement[] stackTrace)
      Reports a fatal or high-severity error to the Driver Station console.

      Use this for constructor failures, missing hardware, or anything that should be immediately visible to operators.

      Parameters:
      message - error description
      stackTrace - stack trace to include, or null to omit
    • reportWarning

      public static void reportWarning(String message, boolean printStackTrace)
      Reports a recoverable warning to the Driver Station console.

      Use this for situations like a missing starting pose or an auto file that was not pre-loaded.

      Parameters:
      message - warning description
      printStackTrace - true to include a stack trace in the output
    • silenceJoystickConnectionWarning

      public static void silenceJoystickConnectionWarning(boolean silence)
      Silences the joystick connection warning that fires in simulation when no controllers are plugged in.
      Parameters:
      silence - true to suppress the warning