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). 044 * 045 * <p>When connected to the real field, this number only changes in full integer increments, and 046 * always counts down. 047 * 048 * <p>When the DS is in practice mode, this number is a floating point number, and counts down. 049 * 050 * <p>When the DS is in teleop or autonomous mode, this number returns -1.0. 051 * 052 * <p>Simulation matches DS behavior without an FMS connected. 053 * 054 * @return Time remaining in current match period (auto or teleop) in seconds 055 */ 056 public static double getMatchTime() { 057 return DriverStation.getMatchTime(); 058 } 059 060 /** 061 * Pause the execution of the thread for a specified period of time. Motors will continue to run 062 * at their last assigned values, and sensors will continue to update. Only the task containing 063 * the wait will pause until the wait time is expired. 064 * 065 * @param period Length of time to pause 066 */ 067 public static void delay(final Time period) { 068 delay(period.in(Seconds)); 069 } 070 071 /** 072 * Pause the execution of the thread for a specified period of time given in seconds. Motors will 073 * continue to run at their last assigned values, and sensors will continue to update. Only the 074 * task containing the wait will pause until the wait time is expired. 075 * 076 * @param seconds Length of time to pause 077 */ 078 public static void delay(final double seconds) { 079 try { 080 Thread.sleep((long) (seconds * 1e3)); 081 } catch (final InterruptedException ex) { 082 Thread.currentThread().interrupt(); 083 } 084 } 085 086 private double m_startTime; 087 private double m_accumulatedTime; 088 private boolean m_running; 089 090 /** Timer constructor. */ 091 public Timer() { 092 reset(); 093 } 094 095 private double getMsClock() { 096 return RobotController.getTime() / 1000.0; 097 } 098 099 /** 100 * Get the current time from the timer. If the clock is running it is derived from the current 101 * system clock the start time stored in the timer class. If the clock is not running, then return 102 * the time when it was last stopped. 103 * 104 * @return Current time value for this timer in seconds 105 */ 106 public double get() { 107 if (m_running) { 108 return m_accumulatedTime + (getMsClock() - m_startTime) / 1000.0; 109 } else { 110 return m_accumulatedTime; 111 } 112 } 113 114 /** 115 * Reset the timer by setting the time to 0. 116 * 117 * <p>Make the timer startTime the current time so new requests will be relative now. 118 */ 119 public final void reset() { 120 m_accumulatedTime = 0; 121 m_startTime = getMsClock(); 122 } 123 124 /** 125 * Start the timer running. Just set the running flag to true indicating that all time requests 126 * should be relative to the system clock. Note that this method is a no-op if the timer is 127 * already running. 128 */ 129 public void start() { 130 if (!m_running) { 131 m_startTime = getMsClock(); 132 m_running = true; 133 } 134 } 135 136 /** 137 * Restart the timer by stopping the timer, if it is not already stopped, resetting the 138 * accumulated time, then starting the timer again. If you want an event to periodically reoccur 139 * at some time interval from the start time, consider using advanceIfElapsed() instead. 140 */ 141 public void restart() { 142 if (m_running) { 143 stop(); 144 } 145 reset(); 146 start(); 147 } 148 149 /** 150 * Stop the timer. This computes the time as of now and clears the running flag, causing all 151 * subsequent time requests to be read from the accumulated time rather than looking at the system 152 * clock. 153 */ 154 public void stop() { 155 m_accumulatedTime = get(); 156 m_running = false; 157 } 158 159 /** 160 * Check if the period specified has passed. 161 * 162 * @param period The period to check. 163 * @return Whether the period has passed. 164 */ 165 public boolean hasElapsed(Time period) { 166 return hasElapsed(period.in(Seconds)); 167 } 168 169 /** 170 * Check if the period specified has passed. 171 * 172 * @param seconds The period to check in seconds. 173 * @return Whether the period has passed. 174 */ 175 public boolean hasElapsed(double seconds) { 176 return get() >= seconds; 177 } 178 179 /** 180 * Check if the period specified has passed and if it has, advance the start time by that period. 181 * This is useful to decide if it's time to do periodic work without drifting later by the time it 182 * took to get around to checking. 183 * 184 * @param seconds The period to check. 185 * @return Whether the period has passed. 186 */ 187 public boolean advanceIfElapsed(double seconds) { 188 if (get() >= seconds) { 189 // Advance the start time by the period. 190 // Don't set it to the current time... we want to avoid drift. 191 m_startTime += seconds * 1000; 192 return true; 193 } else { 194 return false; 195 } 196 } 197 198 /** 199 * Whether the timer is currently running. 200 * 201 * @return true if running. 202 */ 203 public boolean isRunning() { 204 return m_running; 205 } 206}