001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) FIRST 2016-2017. All Rights Reserved. */ 003/* Open Source Software - may be modified and shared by FRC teams. The code */ 004/* must be accompanied by the FIRST BSD license file in the root directory of */ 005/* the project. */ 006/*----------------------------------------------------------------------------*/ 007 008package edu.wpi.first.wpilibj; 009 010import edu.wpi.first.wpilibj.util.BaseSystemNotInitializedException; 011 012public class Timer { 013 private static StaticInterface impl; 014 015 @SuppressWarnings("MethodName") 016 public static void SetImplementation(StaticInterface ti) { 017 impl = ti; 018 } 019 020 /** 021 * Return the system clock time in seconds. Return the time from the FPGA hardware clock in 022 * seconds since the FPGA started. 023 * 024 * @return Robot running time in seconds. 025 */ 026 @SuppressWarnings("AbbreviationAsWordInName") 027 public static double getFPGATimestamp() { 028 if (impl != null) { 029 return impl.getFPGATimestamp(); 030 } else { 031 throw new BaseSystemNotInitializedException(StaticInterface.class, Timer.class); 032 } 033 } 034 035 /** 036 * Return the approximate match time The FMS does not currently send the official match time to 037 * the robots This returns the time since the enable signal sent from the Driver Station At the 038 * beginning of autonomous, the time is reset to 0.0 seconds At the beginning of teleop, the time 039 * is reset to +15.0 seconds If the robot is disabled, this returns 0.0 seconds Warning: This is 040 * not an official time (so it cannot be used to argue with referees). 041 * 042 * @return Match time in seconds since the beginning of autonomous 043 */ 044 public static double getMatchTime() { 045 if (impl != null) { 046 return impl.getMatchTime(); 047 } else { 048 throw new BaseSystemNotInitializedException(StaticInterface.class, Timer.class); 049 } 050 } 051 052 /** 053 * Pause the thread for a specified time. Pause the execution of the thread for a specified period 054 * of time given in seconds. Motors will continue to run at their last assigned values, and 055 * sensors will continue to update. Only the task containing the wait will pause until the wait 056 * time is expired. 057 * 058 * @param seconds Length of time to pause 059 */ 060 public static void delay(final double seconds) { 061 if (impl != null) { 062 impl.delay(seconds); 063 } else { 064 throw new BaseSystemNotInitializedException(StaticInterface.class, Timer.class); 065 } 066 } 067 068 public interface StaticInterface { 069 @SuppressWarnings("AbbreviationAsWordInName") 070 double getFPGATimestamp(); 071 072 double getMatchTime(); 073 074 void delay(final double seconds); 075 076 @SuppressWarnings("JavadocMethod") 077 Interface newTimer(); 078 } 079 080 private final Interface m_timer; 081 082 @SuppressWarnings("JavadocMethod") 083 public Timer() { 084 if (impl != null) { 085 m_timer = impl.newTimer(); 086 } else { 087 throw new BaseSystemNotInitializedException(StaticInterface.class, Timer.class); 088 } 089 } 090 091 /** 092 * Get the current time from the timer. If the clock is running it is derived from the current 093 * system clock the start time stored in the timer class. If the clock is not running, then return 094 * the time when it was last stopped. 095 * 096 * @return Current time value for this timer in seconds 097 */ 098 public double get() { 099 return m_timer.get(); 100 } 101 102 /** 103 * Reset the timer by setting the time to 0. Make the timer startTime the current time so new 104 * requests will be relative now 105 */ 106 public void reset() { 107 m_timer.reset(); 108 } 109 110 /** 111 * Start the timer running. Just set the running flag to true indicating that all time requests 112 * should be relative to the system clock. 113 */ 114 public void start() { 115 m_timer.start(); 116 } 117 118 /** 119 * Stop the timer. This computes the time as of now and clears the running flag, causing all 120 * subsequent time requests to be read from the accumulated time rather than looking at the system 121 * clock. 122 */ 123 public void stop() { 124 m_timer.stop(); 125 } 126 127 /** 128 * Check if the period specified has passed and if it has, advance the start time by that period. 129 * This is useful to decide if it's time to do periodic work without drifting later by the time it 130 * took to get around to checking. 131 * 132 * @param period The period to check for (in seconds). 133 * @return If the period has passed. 134 */ 135 public boolean hasPeriodPassed(double period) { 136 return m_timer.hasPeriodPassed(period); 137 } 138 139 public interface Interface { 140 /** 141 * Get the current time from the timer. If the clock is running it is derived from the current 142 * system clock the start time stored in the timer class. If the clock is not running, then 143 * return the time when it was last stopped. 144 * 145 * @return Current time value for this timer in seconds 146 */ 147 double get(); 148 149 /** 150 * Reset the timer by setting the time to 0. Make the timer startTime the current time so new 151 * requests will be relative now 152 */ 153 void reset(); 154 155 /** 156 * Start the timer running. Just set the running flag to true indicating that all time requests 157 * should be relative to the system clock. 158 */ 159 void start(); 160 161 /** 162 * Stop the timer. This computes the time as of now and clears the running flag, causing all 163 * subsequent time requests to be read from the accumulated time rather than looking at the 164 * system clock. 165 */ 166 void stop(); 167 168 169 /** 170 * Check if the period specified has passed and if it has, advance the start time by that 171 * period. This is useful to decide if it's time to do periodic work without drifting later by 172 * the time it took to get around to checking. 173 * 174 * @param period The period to check for (in seconds). 175 * @return If the period has passed. 176 */ 177 boolean hasPeriodPassed(double period); 178 } 179}