Brian Silverman | f7f267a | 2017-02-04 16:16:08 -0800 | [diff] [blame^] | 1 | /*----------------------------------------------------------------------------*/ |
| 2 | /* Copyright (c) FIRST 2008-2017. All Rights Reserved. */ |
| 3 | /* Open Source Software - may be modified and shared by FRC teams. The code */ |
| 4 | /* must be accompanied by the FIRST BSD license file in the root directory of */ |
| 5 | /* the project. */ |
| 6 | /*----------------------------------------------------------------------------*/ |
| 7 | |
| 8 | #include "Timer.h" |
| 9 | |
| 10 | #include <chrono> |
| 11 | #include <iostream> |
| 12 | #include <thread> |
| 13 | |
| 14 | #include "DriverStation.h" |
| 15 | #include "HAL/HAL.h" |
| 16 | #include "Utility.h" |
| 17 | |
| 18 | namespace frc { |
| 19 | |
| 20 | /** |
| 21 | * Pause the task for a specified time. |
| 22 | * |
| 23 | * Pause the execution of the program for a specified period of time given in |
| 24 | * seconds. Motors will continue to run at their last assigned values, and |
| 25 | * sensors will continue to update. Only the task containing the wait will |
| 26 | * pause until the wait time is expired. |
| 27 | * |
| 28 | * @param seconds Length of time to pause, in seconds. |
| 29 | */ |
| 30 | void Wait(double seconds) { |
| 31 | if (seconds < 0.0) return; |
| 32 | std::this_thread::sleep_for(std::chrono::duration<double>(seconds)); |
| 33 | } |
| 34 | |
| 35 | /** |
| 36 | * Return the FPGA system clock time in seconds. |
| 37 | * This is deprecated and just forwards to Timer::GetFPGATimestamp(). |
| 38 | * @return Robot running time in seconds. |
| 39 | */ |
| 40 | double GetClock() { return Timer::GetFPGATimestamp(); } |
| 41 | |
| 42 | /** |
| 43 | * @brief Gives real-time clock system time with nanosecond resolution |
| 44 | * @return The time, just in case you want the robot to start autonomous at 8pm |
| 45 | * on Saturday. |
| 46 | */ |
| 47 | double GetTime() { |
| 48 | using namespace std::chrono; |
| 49 | return duration_cast<duration<double>>(system_clock::now().time_since_epoch()) |
| 50 | .count(); |
| 51 | } |
| 52 | |
| 53 | } // namespace frc |
| 54 | |
| 55 | using namespace frc; |
| 56 | |
| 57 | // for compatibility with msvc12--see C2864 |
| 58 | const double Timer::kRolloverTime = (1ll << 32) / 1e6; |
| 59 | /** |
| 60 | * Create a new timer object. |
| 61 | * |
| 62 | * Create a new timer object and reset the time to zero. The timer is initially |
| 63 | * not running and |
| 64 | * must be started. |
| 65 | */ |
| 66 | Timer::Timer() { |
| 67 | // Creates a semaphore to control access to critical regions. |
| 68 | // Initially 'open' |
| 69 | Reset(); |
| 70 | } |
| 71 | |
| 72 | /** |
| 73 | * Get the current time from the timer. If the clock is running it is derived |
| 74 | * from the current system clock the start time stored in the timer class. If |
| 75 | * the clock is not running, then return the time when it was last stopped. |
| 76 | * |
| 77 | * @return Current time value for this timer in seconds |
| 78 | */ |
| 79 | double Timer::Get() const { |
| 80 | double result; |
| 81 | double currentTime = GetFPGATimestamp(); |
| 82 | |
| 83 | std::lock_guard<priority_mutex> sync(m_mutex); |
| 84 | if (m_running) { |
| 85 | // If the current time is before the start time, then the FPGA clock |
| 86 | // rolled over. Compensate by adding the ~71 minutes that it takes |
| 87 | // to roll over to the current time. |
| 88 | if (currentTime < m_startTime) { |
| 89 | currentTime += kRolloverTime; |
| 90 | } |
| 91 | |
| 92 | result = (currentTime - m_startTime) + m_accumulatedTime; |
| 93 | } else { |
| 94 | result = m_accumulatedTime; |
| 95 | } |
| 96 | |
| 97 | return result; |
| 98 | } |
| 99 | |
| 100 | /** |
| 101 | * Reset the timer by setting the time to 0. |
| 102 | * |
| 103 | * Make the timer startTime the current time so new requests will be relative to |
| 104 | * now. |
| 105 | */ |
| 106 | void Timer::Reset() { |
| 107 | std::lock_guard<priority_mutex> sync(m_mutex); |
| 108 | m_accumulatedTime = 0; |
| 109 | m_startTime = GetFPGATimestamp(); |
| 110 | } |
| 111 | |
| 112 | /** |
| 113 | * Start the timer running. |
| 114 | * |
| 115 | * Just set the running flag to true indicating that all time requests should be |
| 116 | * relative to the system clock. |
| 117 | */ |
| 118 | void Timer::Start() { |
| 119 | std::lock_guard<priority_mutex> sync(m_mutex); |
| 120 | if (!m_running) { |
| 121 | m_startTime = GetFPGATimestamp(); |
| 122 | m_running = true; |
| 123 | } |
| 124 | } |
| 125 | |
| 126 | /** |
| 127 | * Stop the timer. |
| 128 | * |
| 129 | * This computes the time as of now and clears the running flag, causing all |
| 130 | * subsequent time requests to be read from the accumulated time rather than |
| 131 | * looking at the system clock. |
| 132 | */ |
| 133 | void Timer::Stop() { |
| 134 | double temp = Get(); |
| 135 | |
| 136 | std::lock_guard<priority_mutex> sync(m_mutex); |
| 137 | if (m_running) { |
| 138 | m_accumulatedTime = temp; |
| 139 | m_running = false; |
| 140 | } |
| 141 | } |
| 142 | |
| 143 | /** |
| 144 | * Check if the period specified has passed and if it has, advance the start |
| 145 | * time by that period. This is useful to decide if it's time to do periodic |
| 146 | * work without drifting later by the time it took to get around to checking. |
| 147 | * |
| 148 | * @param period The period to check for (in seconds). |
| 149 | * @return True if the period has passed. |
| 150 | */ |
| 151 | bool Timer::HasPeriodPassed(double period) { |
| 152 | if (Get() > period) { |
| 153 | std::lock_guard<priority_mutex> sync(m_mutex); |
| 154 | // Advance the start time by the period. |
| 155 | m_startTime += period; |
| 156 | // Don't set it to the current time... we want to avoid drift. |
| 157 | return true; |
| 158 | } |
| 159 | return false; |
| 160 | } |
| 161 | |
| 162 | /** |
| 163 | * Return the FPGA system clock time in seconds. |
| 164 | * |
| 165 | * Return the time from the FPGA hardware clock in seconds since the FPGA |
| 166 | * started. Rolls over after 71 minutes. |
| 167 | * |
| 168 | * @returns Robot running time in seconds. |
| 169 | */ |
| 170 | double Timer::GetFPGATimestamp() { |
| 171 | // FPGA returns the timestamp in microseconds |
| 172 | // Call the helper GetFPGATime() in Utility.cpp |
| 173 | return GetFPGATime() * 1.0e-6; |
| 174 | } |
| 175 | |
| 176 | /** |
| 177 | * Return the approximate match time The FMS does not currently send the |
| 178 | * official match time to |
| 179 | * the robots This returns the time since the enable signal sent from the Driver |
| 180 | * Station At the |
| 181 | * beginning of autonomous, the time is reset to 0.0 seconds At the beginning of |
| 182 | * teleop, the time |
| 183 | * is reset to +15.0 seconds If the robot is disabled, this returns 0.0 seconds |
| 184 | * Warning: This is |
| 185 | * not an official time (so it cannot be used to argue with referees). |
| 186 | * |
| 187 | * @return Match time in seconds since the beginning of autonomous |
| 188 | */ |
| 189 | double Timer::GetMatchTime() { |
| 190 | return DriverStation::GetInstance().GetMatchTime(); |
| 191 | } |