WPILibC++ 2024.3.2
Timer.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <units/time.h>
8
9namespace frc {
10
11/**
12 * Pause the task for a specified time.
13 *
14 * Pause the execution of the program for a specified period of time given in
15 * seconds. Motors will continue to run at their last assigned values, and
16 * sensors will continue to update. Only the task containing the wait will pause
17 * until the wait time is expired.
18 *
19 * @param seconds Length of time to pause, in seconds.
20 */
21void Wait(units::second_t seconds);
22
23/**
24 * @brief Gives real-time clock system time with nanosecond resolution
25 * @return The time, just in case you want the robot to start autonomous at 8pm
26 * on Saturday.
27 */
28units::second_t GetTime();
29
30/**
31 * A timer class.
32 *
33 * Note that if the user calls frc::sim::RestartTiming(), they should also reset
34 * the timer so Get() won't return a negative duration.
35 */
36class Timer {
37 public:
38 /**
39 * Create a new timer object.
40 *
41 * Create a new timer object and reset the time to zero. The timer is
42 * initially not running and must be started.
43 */
45
46 virtual ~Timer() = default;
47
48 Timer(const Timer&) = default;
49 Timer& operator=(const Timer&) = default;
50 Timer(Timer&&) = default;
51 Timer& operator=(Timer&&) = default;
52
53 /**
54 * Get the current time from the timer. If the clock is running it is derived
55 * from the current system clock the start time stored in the timer class. If
56 * the clock is not running, then return the time when it was last stopped.
57 *
58 * @return Current time value for this timer in seconds
59 */
60 units::second_t Get() const;
61
62 /**
63 * Reset the timer by setting the time to 0.
64 *
65 * Make the timer startTime the current time so new requests will be relative
66 * to now.
67 */
68 void Reset();
69
70 /**
71 * Start the timer running.
72 *
73 * Just set the running flag to true indicating that all time requests should
74 * be relative to the system clock. Note that this method is a no-op if the
75 * timer is already running.
76 */
77 void Start();
78
79 /**
80 * Restart the timer by stopping the timer, if it is not already stopped,
81 * resetting the accumulated time, then starting the timer again. If you
82 * want an event to periodically reoccur at some time interval from the
83 * start time, consider using AdvanceIfElapsed() instead.
84 */
85 void Restart();
86
87 /**
88 * Stop the timer.
89 *
90 * This computes the time as of now and clears the running flag, causing all
91 * subsequent time requests to be read from the accumulated time rather than
92 * looking at the system clock.
93 */
94 void Stop();
95
96 /**
97 * Check if the period specified has passed.
98 *
99 * @param period The period to check.
100 * @return True if the period has passed.
101 */
102 bool HasElapsed(units::second_t period) const;
103
104 /**
105 * Check if the period specified has passed and if it has, advance the start
106 * time by that period. This is useful to decide if it's time to do periodic
107 * work without drifting later by the time it took to get around to checking.
108 *
109 * @param period The period to check for.
110 * @return True if the period has passed.
111 */
112 bool AdvanceIfElapsed(units::second_t period);
113
114 /**
115 * Return the FPGA system clock time in seconds.
116 *
117 * Return the time from the FPGA hardware clock in seconds since the FPGA
118 * started. Rolls over after 71 minutes.
119 *
120 * @returns Robot running time in seconds.
121 */
122 static units::second_t GetFPGATimestamp();
123
124 /**
125 * Return the approximate match time.
126 *
127 * The FMS does not send an official match time to the robots, but does send
128 * an approximate match time. The value will count down the time remaining in
129 * the current period (auto or teleop).
130 *
131 * Warning: This is not an official time (so it cannot be used to dispute ref
132 * calls or guarantee that a function will trigger before the match ends).
133 *
134 * The Practice Match function of the DS approximates the behavior seen on the
135 * field.
136 *
137 * @return Time remaining in current match period (auto or teleop)
138 */
139 static units::second_t GetMatchTime();
140
141 private:
142 units::second_t m_startTime = 0_s;
143 units::second_t m_accumulatedTime = 0_s;
144 bool m_running = false;
145};
146
147} // namespace frc
A timer class.
Definition: Timer.h:36
void Restart()
Restart the timer by stopping the timer, if it is not already stopped, resetting the accumulated time...
static units::second_t GetFPGATimestamp()
Return the FPGA system clock time in seconds.
bool AdvanceIfElapsed(units::second_t period)
Check if the period specified has passed and if it has, advance the start time by that period.
Timer()
Create a new timer object.
virtual ~Timer()=default
units::second_t Get() const
Get the current time from the timer.
bool HasElapsed(units::second_t period) const
Check if the period specified has passed.
void Reset()
Reset the timer by setting the time to 0.
static units::second_t GetMatchTime()
Return the approximate match time.
Timer & operator=(Timer &&)=default
Timer(const Timer &)=default
Timer(Timer &&)=default
void Start()
Start the timer running.
Timer & operator=(const Timer &)=default
void Stop()
Stop the timer.
Definition: AprilTagPoseEstimator.h:15
void Wait(units::second_t seconds)
Pause the task for a specified time.
units::second_t GetTime()
Gives real-time clock system time with nanosecond resolution.