public static boolean isDisabled() { if (m_impl != null) { return m_impl.isDisabled(); } else { throw new BaseSystemNotInitializedException(Interface.class, RobotState.class); } }
public static boolean isEnabled() { if (m_impl != null) { return m_impl.isEnabled(); } else { throw new BaseSystemNotInitializedException(Interface.class, RobotState.class); } }
public static boolean isOperatorControl() { if (m_impl != null) { return m_impl.isOperatorControl(); } else { throw new BaseSystemNotInitializedException(Interface.class, RobotState.class); } }
public static boolean isAutonomous() { if (m_impl != null) { return m_impl.isAutonomous(); } else { throw new BaseSystemNotInitializedException(Interface.class, RobotState.class); } }
public static boolean isTest() { if (m_impl != null) { return m_impl.isTest(); } else { throw new BaseSystemNotInitializedException(Interface.class, RobotState.class); } }
/** * Return the system clock time in seconds. Return the time from the FPGA hardware clock in * seconds since the FPGA started. * * @return Robot running time in seconds. */ @SuppressWarnings("AbbreviationAsWordInName") public static double getFPGATimestamp() { if (impl != null) { return impl.getFPGATimestamp(); } else { throw new BaseSystemNotInitializedException(StaticInterface.class, Timer.class); } }
@SuppressWarnings("JavadocMethod") public Timer() { if (impl != null) { m_timer = impl.newTimer(); } else { throw new BaseSystemNotInitializedException(StaticInterface.class, Timer.class); } }
public static void reportScheduler() { if (impl != null) { impl.reportScheduler(); } else { throw new BaseSystemNotInitializedException(Interface.class, HLUsageReporting.class); } }
public static void reportPIDController(int num) { if (impl != null) { impl.reportPIDController(num); } else { throw new BaseSystemNotInitializedException(Interface.class, HLUsageReporting.class); } }
public static void reportSmartDashboard() { if (impl != null) { impl.reportSmartDashboard(); } else { throw new BaseSystemNotInitializedException(Interface.class, HLUsageReporting.class); } }
private double getTime() { double time = System.currentTimeMillis() / 1000.0; try { time = Timer.getFPGATimestamp(); } catch (BaseSystemNotInitializedException e) { } return time; }
public static boolean isDisabled() { if(m_impl != null) { return m_impl.isDisabled(); } else { throw new BaseSystemNotInitializedException(Interface.class, RobotStateF.class); } }
public static boolean isEnabled() { if(m_impl != null) { return m_impl.isEnabled(); } else { throw new BaseSystemNotInitializedException(Interface.class, RobotStateF.class); } }
public static boolean isOperatorControl() { if(m_impl != null) { return m_impl.isOperatorControl(); } else { throw new BaseSystemNotInitializedException(Interface.class, RobotStateF.class); } }
public static boolean isAutonomous() { if(m_impl != null) { return m_impl.isAutonomous(); } else { throw new BaseSystemNotInitializedException(Interface.class, RobotStateF.class); } }
public static boolean isTest() { if(m_impl != null) { return m_impl.isTest(); } else { throw new BaseSystemNotInitializedException(Interface.class, RobotStateF.class); } }
/** * Return the approximate match time The FMS does not currently send the official match time to * the robots This returns the time since the enable signal sent from the Driver Station At the * beginning of autonomous, the time is reset to 0.0 seconds At the beginning of teleop, the time * is reset to +15.0 seconds If the robot is disabled, this returns 0.0 seconds Warning: This is * not an official time (so it cannot be used to argue with referees). * * @return Match time in seconds since the beginning of autonomous */ public static double getMatchTime() { if (impl != null) { return impl.getMatchTime(); } else { throw new BaseSystemNotInitializedException(StaticInterface.class, Timer.class); } }
/** * Pause the thread for a specified time. Pause the execution of the thread for a specified period * of time given in seconds. Motors will continue to run at their last assigned values, and * sensors will continue to update. Only the task containing the wait will pause until the wait * time is expired. * * @param seconds Length of time to pause */ public static void delay(final double seconds) { if (impl != null) { impl.delay(seconds); } else { throw new BaseSystemNotInitializedException(StaticInterface.class, Timer.class); } }