001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) FIRST 2008-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.internal; 009 010import edu.wpi.first.wpilibj.DriverStation; 011import edu.wpi.first.wpilibj.Timer; 012import edu.wpi.first.wpilibj.Utility; 013 014/** 015 * Timer objects measure accumulated time in milliseconds. The timer object functions like a 016 * stopwatch. It can be started, stopped, and cleared. When the timer is running its value counts 017 * up in milliseconds. When stopped, the timer holds the current value. The implementation simply 018 * records the time when started and subtracts the current time whenever the value is requested. 019 */ 020public class HardwareTimer implements Timer.StaticInterface { 021 /** 022 * Pause the thread for a specified time. Pause the execution of the thread for a specified period 023 * of time given in seconds. Motors will continue to run at their last assigned values, and 024 * sensors will continue to update. Only the task containing the wait will pause until the wait 025 * time is expired. 026 * 027 * @param seconds Length of time to pause 028 */ 029 @Override 030 public void delay(final double seconds) { 031 try { 032 Thread.sleep((long) (seconds * 1e3)); 033 } catch (final InterruptedException ex) { 034 Thread.currentThread().interrupt(); 035 } 036 } 037 038 /** 039 * Return the system clock time in seconds. Return the time from the FPGA hardware clock in 040 * seconds since the FPGA started. 041 * 042 * @return Robot running time in seconds. 043 */ 044 @Override 045 public double getFPGATimestamp() { 046 return Utility.getFPGATime() / 1000000.0; 047 } 048 049 @Override 050 public double getMatchTime() { 051 return DriverStation.getInstance().getMatchTime(); 052 } 053 054 @Override 055 public Timer.Interface newTimer() { 056 return new TimerImpl(); 057 } 058 059 class TimerImpl implements Timer.Interface { 060 private double m_startTime; 061 private double m_accumulatedTime; 062 private boolean m_running; 063 064 /** 065 * Create a new timer object. Create a new timer object and reset the time to zero. The timer is 066 * initially not running and must be started. 067 */ 068 public TimerImpl() { 069 reset(); 070 } 071 072 private double getMsClock() { 073 return Utility.getFPGATime() / 1000.0; 074 } 075 076 /** 077 * Get the current time from the timer. If the clock is running it is derived from the current 078 * system clock the start time stored in the timer class. If the clock is not running, then 079 * return the time when it was last stopped. 080 * 081 * @return Current time value for this timer in seconds 082 */ 083 public synchronized double get() { 084 if (m_running) { 085 return ((getMsClock() - m_startTime) + m_accumulatedTime) / 1000.0; 086 } else { 087 return m_accumulatedTime; 088 } 089 } 090 091 /** 092 * Reset the timer by setting the time to 0. Make the timer start time the current time so new 093 * requests will be relative now 094 */ 095 public synchronized void reset() { 096 m_accumulatedTime = 0; 097 m_startTime = getMsClock(); 098 } 099 100 /** 101 * Start the timer running. Just set the running flag to true indicating that all time 102 * requests should be relative to the system clock. 103 */ 104 public synchronized void start() { 105 m_startTime = getMsClock(); 106 m_running = true; 107 } 108 109 /** 110 * Stop the timer. This computes the time as of now and clears the running flag, causing all 111 * subsequent time requests to be read from the accumulated time rather than looking at the 112 * system clock. 113 */ 114 public synchronized void stop() { 115 final double temp = get(); 116 m_accumulatedTime = temp; 117 m_running = false; 118 } 119 120 /** 121 * Check if the period specified has passed and if it has, advance the start time by that 122 * period. This is useful to decide if it's time to do periodic work without drifting later by 123 * the time it took to get around to checking. 124 * 125 * @param period The period to check for (in seconds). 126 * @return If the period has passed. 127 */ 128 public synchronized boolean hasPeriodPassed(double period) { 129 if (get() > period) { 130 // Advance the start time by the period. 131 // Don't set it to the current time... we want to avoid drift. 132 m_startTime += period * 1000; 133 return true; 134 } 135 return false; 136 } 137 } 138}