001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.wpilibj; 006 007import static edu.wpi.first.units.Units.Seconds; 008 009import edu.wpi.first.units.measure.Time; 010 011/** 012 * A timer class. 013 * 014 * <p>Note that if the user calls SimHooks.restartTiming(), they should also reset the timer so 015 * get() won't return a negative duration. 016 */ 017public class Timer { 018 /** 019 * Return the clock time in seconds. By default, the time is based on the FPGA hardware clock in 020 * seconds since the FPGA started. However, the return value of this method may be modified to use 021 * any time base, including non-monotonic time bases. 022 * 023 * @return Robot running time in seconds. 024 */ 025 public static double getTimestamp() { 026 return RobotController.getTime() / 1000000.0; 027 } 028 029 /** 030 * Return the system clock time in seconds. Return the time from the FPGA hardware clock in 031 * seconds since the FPGA started. 032 * 033 * @return Robot running time in seconds. 034 */ 035 public static double getFPGATimestamp() { 036 return RobotController.getFPGATime() / 1000000.0; 037 } 038 039 /** 040 * Return the approximate match time. The FMS does not send an official match time to the robots, 041 * but does send an approximate match time. The value will count down the time remaining in the 042 * current period (auto or teleop). Warning: This is not an official time (so it cannot be used to 043 * dispute ref calls or guarantee that a function will trigger before the match ends) The Practice 044 * Match function of the DS approximates the behavior seen on the field. 045 * 046 * @return Time remaining in current match period (auto or teleop) in seconds 047 */ 048 public static double getMatchTime() { 049 return DriverStation.getMatchTime(); 050 } 051 052 /** 053 * Pause the execution of the thread for a specified period of time. Motors will continue to run 054 * at their last assigned values, and sensors will continue to update. Only the task containing 055 * the wait will pause until the wait time is expired. 056 * 057 * @param period Length of time to pause 058 */ 059 public static void delay(final Time period) { 060 delay(period.in(Seconds)); 061 } 062 063 /** 064 * Pause the execution of the thread for a specified period of time given in seconds. Motors will 065 * continue to run at their last assigned values, and sensors will continue to update. Only the 066 * task containing the wait will pause until the wait time is expired. 067 * 068 * @param seconds Length of time to pause 069 */ 070 public static void delay(final double seconds) { 071 try { 072 Thread.sleep((long) (seconds * 1e3)); 073 } catch (final InterruptedException ex) { 074 Thread.currentThread().interrupt(); 075 } 076 } 077 078 private double m_startTime; 079 private double m_accumulatedTime; 080 private boolean m_running; 081 082 /** Timer constructor. */ 083 public Timer() { 084 reset(); 085 } 086 087 private double getMsClock() { 088 return RobotController.getTime() / 1000.0; 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 if (m_running) { 100 return m_accumulatedTime + (getMsClock() - m_startTime) / 1000.0; 101 } else { 102 return m_accumulatedTime; 103 } 104 } 105 106 /** 107 * Reset the timer by setting the time to 0. 108 * 109 * <p>Make the timer startTime the current time so new requests will be relative now. 110 */ 111 public final void reset() { 112 m_accumulatedTime = 0; 113 m_startTime = getMsClock(); 114 } 115 116 /** 117 * Start the timer running. Just set the running flag to true indicating that all time requests 118 * should be relative to the system clock. Note that this method is a no-op if the timer is 119 * already running. 120 */ 121 public void start() { 122 if (!m_running) { 123 m_startTime = getMsClock(); 124 m_running = true; 125 } 126 } 127 128 /** 129 * Restart the timer by stopping the timer, if it is not already stopped, resetting the 130 * accumulated time, then starting the timer again. If you want an event to periodically reoccur 131 * at some time interval from the start time, consider using advanceIfElapsed() instead. 132 */ 133 public void restart() { 134 if (m_running) { 135 stop(); 136 } 137 reset(); 138 start(); 139 } 140 141 /** 142 * Stop the timer. This computes the time as of now and clears the running flag, causing all 143 * subsequent time requests to be read from the accumulated time rather than looking at the system 144 * clock. 145 */ 146 public void stop() { 147 m_accumulatedTime = get(); 148 m_running = false; 149 } 150 151 /** 152 * Check if the period specified has passed. 153 * 154 * @param period The period to check. 155 * @return Whether the period has passed. 156 */ 157 public boolean hasElapsed(Time period) { 158 return hasElapsed(period.in(Seconds)); 159 } 160 161 /** 162 * Check if the period specified has passed. 163 * 164 * @param seconds The period to check in seconds. 165 * @return Whether the period has passed. 166 */ 167 public boolean hasElapsed(double seconds) { 168 return get() >= seconds; 169 } 170 171 /** 172 * Check if the period specified has passed and if it has, advance the start time by that period. 173 * This is useful to decide if it's time to do periodic work without drifting later by the time it 174 * took to get around to checking. 175 * 176 * @param seconds The period to check. 177 * @return Whether the period has passed. 178 */ 179 public boolean advanceIfElapsed(double seconds) { 180 if (get() >= seconds) { 181 // Advance the start time by the period. 182 // Don't set it to the current time... we want to avoid drift. 183 m_startTime += seconds * 1000; 184 return true; 185 } else { 186 return false; 187 } 188 } 189 190 /** 191 * Whether the timer is currently running. 192 * 193 * @return true if running. 194 */ 195 public boolean isRunning() { 196 return m_running; 197 } 198}