Skip to content

Commit 8b99ad8

Browse files
Murat65536SamCarlbergKangarooKoalacalcmogul
authored
[wpilib] Add a few unit overloads (#8231)
Co-authored-by: Sam Carlberg <[email protected]> Co-authored-by: Joseph Eng <[email protected]> Co-authored-by: Tyler Veness <[email protected]>
1 parent 58ba536 commit 8b99ad8

File tree

11 files changed

+182
-9
lines changed

11 files changed

+182
-9
lines changed

wpilibc/src/main/native/cpp/Notifier.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -182,6 +182,10 @@ void Notifier::StartPeriodic(units::second_t period) {
182182
UpdateAlarm();
183183
}
184184

185+
void Notifier::StartPeriodic(units::hertz_t frequency) {
186+
StartPeriodic(1 / frequency);
187+
}
188+
185189
void Notifier::Stop() {
186190
std::scoped_lock lock(m_processMutex);
187191
m_periodic = false;

wpilibc/src/main/native/cpp/TimedRobot.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,8 @@ TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) {
9191
HALUsageReporting::kFramework_Timed);
9292
}
9393

94+
TimedRobot::TimedRobot(units::hertz_t frequency) : TimedRobot{1 / frequency} {}
95+
9496
TimedRobot::~TimedRobot() {
9597
if (m_notifier != HAL_kInvalidHandle) {
9698
int32_t status = 0;

wpilibc/src/main/native/include/frc/Notifier.h

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
#include <utility>
1515

1616
#include <hal/Types.h>
17+
#include <units/frequency.h>
1718
#include <units/time.h>
1819
#include <wpi/mutex.h>
1920

@@ -107,6 +108,17 @@ class Notifier {
107108
*/
108109
void StartPeriodic(units::second_t period);
109110

111+
/**
112+
* Run the callback periodically with the given frequency.
113+
*
114+
* The user-provided callback should be written so that it completes before
115+
* the next time it's scheduled to run.
116+
*
117+
* @param frequency Frequency after which to call the callback starting one
118+
* period after the call to this method.
119+
*/
120+
void StartPeriodic(units::hertz_t frequency);
121+
110122
/**
111123
* Stop further callback invocations.
112124
*

wpilibc/src/main/native/include/frc/TimedRobot.h

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111

1212
#include <hal/Notifier.h>
1313
#include <hal/Types.h>
14+
#include <units/frequency.h>
1415
#include <units/math.h>
1516
#include <units/time.h>
1617
#include <wpi/priority_queue.h>
@@ -47,10 +48,17 @@ class TimedRobot : public IterativeRobotBase {
4748
/**
4849
* Constructor for TimedRobot.
4950
*
50-
* @param period Period.
51+
* @param period The period of the robot loop function.
5152
*/
5253
explicit TimedRobot(units::second_t period = kDefaultPeriod);
5354

55+
/**
56+
* Constructor for TimedRobot.
57+
*
58+
* @param frequency The frequency of the robot loop function.
59+
*/
60+
explicit TimedRobot(units::hertz_t frequency);
61+
5462
TimedRobot(TimedRobot&&) = default;
5563
TimedRobot& operator=(TimedRobot&&) = default;
5664

wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,12 @@
44

55
package edu.wpi.first.wpilibj;
66

7+
import static edu.wpi.first.units.Units.Seconds;
78
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
89

910
import edu.wpi.first.hal.NotifierJNI;
11+
import edu.wpi.first.units.measure.Frequency;
12+
import edu.wpi.first.units.measure.Time;
1013
import java.util.concurrent.atomic.AtomicInteger;
1114
import java.util.concurrent.locks.ReentrantLock;
1215

@@ -186,6 +189,15 @@ public void startSingle(double delaySeconds) {
186189
}
187190
}
188191

192+
/**
193+
* Run the callback once after the given delay.
194+
*
195+
* @param delay Time to wait before the callback is called.
196+
*/
197+
public void startSingle(Time delay) {
198+
startSingle(delay.in(Seconds));
199+
}
200+
189201
/**
190202
* Run the callback periodically with the given period.
191203
*
@@ -207,6 +219,32 @@ public void startPeriodic(double periodSeconds) {
207219
}
208220
}
209221

222+
/**
223+
* Run the callback periodically with the given period.
224+
*
225+
* <p>The user-provided callback should be written so that it completes before the next time it's
226+
* scheduled to run.
227+
*
228+
* @param period Period after which to call the callback starting one period after the call to
229+
* this method.
230+
*/
231+
public void startPeriodic(Time period) {
232+
startPeriodic(period.in(Seconds));
233+
}
234+
235+
/**
236+
* Run the callback periodically with the given frequency.
237+
*
238+
* <p>The user-provided callback should be written so that it completes before the next time it's
239+
* scheduled to run.
240+
*
241+
* @param frequency Frequency at which to call the callback, starting one period after the call to
242+
* this method.
243+
*/
244+
public void startPeriodic(Frequency frequency) {
245+
startPeriodic(frequency.asPeriod());
246+
}
247+
210248
/**
211249
* Stop further callback invocations.
212250
*

wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java

Lines changed: 20 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111
import edu.wpi.first.hal.FRCNetComm.tResourceType;
1212
import edu.wpi.first.hal.HAL;
1313
import edu.wpi.first.hal.NotifierJNI;
14+
import edu.wpi.first.units.measure.Frequency;
1415
import edu.wpi.first.units.measure.Time;
1516
import java.util.PriorityQueue;
1617

@@ -84,7 +85,7 @@ protected TimedRobot() {
8485
/**
8586
* Constructor for TimedRobot.
8687
*
87-
* @param period Period in seconds.
88+
* @param period The period of the robot loop function.
8889
*/
8990
protected TimedRobot(double period) {
9091
super(period);
@@ -95,6 +96,24 @@ protected TimedRobot(double period) {
9596
HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Timed);
9697
}
9798

99+
/**
100+
* Constructor for TimedRobot.
101+
*
102+
* @param period The period of the robot loop function.
103+
*/
104+
protected TimedRobot(Time period) {
105+
this(period.in(Seconds));
106+
}
107+
108+
/**
109+
* Constructor for TimedRobot.
110+
*
111+
* @param frequency The frequency of the robot loop function.
112+
*/
113+
protected TimedRobot(Frequency frequency) {
114+
this(frequency.asPeriod());
115+
}
116+
98117
@Override
99118
public void close() {
100119
NotifierJNI.stopNotifier(m_notifier);

wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java

Lines changed: 29 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,10 @@
44

55
package edu.wpi.first.wpilibj;
66

7+
import static edu.wpi.first.units.Units.Seconds;
8+
9+
import edu.wpi.first.units.measure.Time;
10+
711
/**
812
* A timer class.
913
*
@@ -46,10 +50,20 @@ public static double getMatchTime() {
4650
}
4751

4852
/**
49-
* Pause the thread for a specified time. Pause the execution of the thread for a specified period
50-
* of time given in seconds. Motors will continue to run at their last assigned values, and
51-
* sensors will continue to update. Only the task containing the wait will pause until the wait
52-
* time is expired.
53+
* Pause the execution of the thread for a specified period of time. Motors will continue to run
54+
* at their last assigned values, and sensors will continue to update. Only the task containing
55+
* the wait will pause until the wait time is expired.
56+
*
57+
* @param period Length of time to pause
58+
*/
59+
public static void delay(final Time period) {
60+
delay(period.in(Seconds));
61+
}
62+
63+
/**
64+
* Pause the execution of the thread for a specified period of time given in seconds. Motors will
65+
* continue to run at their last assigned values, and sensors will continue to update. Only the
66+
* task containing the wait will pause until the wait time is expired.
5367
*
5468
* @param seconds Length of time to pause
5569
*/
@@ -137,7 +151,17 @@ public void stop() {
137151
/**
138152
* Check if the period specified has passed.
139153
*
140-
* @param seconds The period to check.
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.
141165
* @return Whether the period has passed.
142166
*/
143167
public boolean hasElapsed(double seconds) {

wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,10 @@
44

55
package edu.wpi.first.wpilibj;
66

7+
import static edu.wpi.first.units.Units.Seconds;
8+
79
import edu.wpi.first.hal.NotifierJNI;
10+
import edu.wpi.first.units.measure.Time;
811
import java.io.Closeable;
912
import java.util.PriorityQueue;
1013
import java.util.concurrent.locks.ReentrantLock;
@@ -55,6 +58,16 @@ public Watchdog(double timeoutSeconds, Runnable callback) {
5558
m_tracer = new Tracer();
5659
}
5760

61+
/**
62+
* Watchdog constructor.
63+
*
64+
* @param timeout The watchdog's timeout with microsecond resolution.
65+
* @param callback This function is called when the timeout expires.
66+
*/
67+
public Watchdog(Time timeout, Runnable callback) {
68+
this(timeout.in(Seconds), callback);
69+
}
70+
5871
@Override
5972
public void close() {
6073
disable();

wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java

Lines changed: 27 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,11 @@
44

55
package edu.wpi.first.wpilibj.event;
66

7+
import static edu.wpi.first.units.Units.Seconds;
78
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
89

910
import edu.wpi.first.math.filter.Debouncer;
11+
import edu.wpi.first.units.measure.Time;
1012
import java.util.concurrent.atomic.AtomicBoolean;
1113
import java.util.function.BiFunction;
1214
import java.util.function.BooleanSupplier;
@@ -167,7 +169,18 @@ public boolean getAsBoolean() {
167169
* Creates a new debounced event from this event - it will become active when this event has been
168170
* active for longer than the specified period.
169171
*
170-
* @param seconds The debounce period.
172+
* @param period The debounce period.
173+
* @return The debounced event (rising edges debounced only).
174+
*/
175+
public BooleanEvent debounce(Time period) {
176+
return debounce(period.in(Seconds));
177+
}
178+
179+
/**
180+
* Creates a new debounced event from this event - it will become active when this event has been
181+
* active for longer than the specified period.
182+
*
183+
* @param seconds The debounce period in seconds.
171184
* @return The debounced event (rising edges debounced only).
172185
*/
173186
public BooleanEvent debounce(double seconds) {
@@ -178,7 +191,19 @@ public BooleanEvent debounce(double seconds) {
178191
* Creates a new debounced event from this event - it will become active when this event has been
179192
* active for longer than the specified period.
180193
*
181-
* @param seconds The debounce period.
194+
* @param period The debounce period.
195+
* @param type The debounce type.
196+
* @return The debounced event.
197+
*/
198+
public BooleanEvent debounce(Time period, Debouncer.DebounceType type) {
199+
return debounce(period.in(Seconds), type);
200+
}
201+
202+
/**
203+
* Creates a new debounced event from this event - it will become active when this event has been
204+
* active for longer than the specified period.
205+
*
206+
* @param seconds The debounce period in seconds.
182207
* @param type The debounce type.
183208
* @return The debounced event.
184209
*/

wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,11 +4,14 @@
44

55
package edu.wpi.first.wpilibj.smartdashboard;
66

7+
import static edu.wpi.first.units.Units.Meters;
8+
79
import edu.wpi.first.math.geometry.Pose2d;
810
import edu.wpi.first.math.geometry.Rotation2d;
911
import edu.wpi.first.networktables.NTSendable;
1012
import edu.wpi.first.networktables.NTSendableBuilder;
1113
import edu.wpi.first.networktables.NetworkTable;
14+
import edu.wpi.first.units.measure.Distance;
1215
import edu.wpi.first.util.sendable.SendableRegistry;
1316
import java.util.ArrayList;
1417
import java.util.List;
@@ -66,6 +69,17 @@ public synchronized void setRobotPose(double xMeters, double yMeters, Rotation2d
6669
m_objects.get(0).setPose(xMeters, yMeters, rotation);
6770
}
6871

72+
/**
73+
* Set the robot pose from x, y, and rotation.
74+
*
75+
* @param x X location
76+
* @param y Y location
77+
* @param rotation rotation
78+
*/
79+
public synchronized void setRobotPose(Distance x, Distance y, Rotation2d rotation) {
80+
m_objects.get(0).setPose(x.in(Meters), y.in(Meters), rotation);
81+
}
82+
6983
/**
7084
* Get the robot pose.
7185
*

0 commit comments

Comments
 (0)