Skip to content
Open
Show file tree
Hide file tree
Changes from 28 commits
Commits
Show all changes
35 commits
Select commit Hold shift + click to select a range
a33cfdc
Add a few unit overloads.
Murat65536 Sep 16, 2025
3d94afa
Remove `Frequency` overload in `startSingle`.
Murat65536 Sep 17, 2025
9debc15
Apply suggestion
Murat65536 Sep 17, 2025
a5a895f
Fix `debounce` `Frequency` javadoc.
Murat65536 Sep 17, 2025
6147d2a
Fix `debounce` parameter name.
Murat65536 Sep 17, 2025
912c745
Merge branch 'unit-overloads' of https://github.com/Murat65536/allwpi…
Murat65536 Sep 17, 2025
ed37170
Apply suggestion
Murat65536 Sep 17, 2025
ff9ab71
Fix `debounce` javadoc.
Murat65536 Sep 17, 2025
ba468e1
Fix `debounce` parameter name.
Murat65536 Sep 17, 2025
1b1d81d
Apply suggestion
Murat65536 Sep 17, 2025
4627280
Apply suggestion from @SamCarlberg
Murat65536 Sep 17, 2025
af04a3c
Fix `delay` javadoc.
Murat65536 Sep 17, 2025
b6dc355
Remove `Frequency` overload on `Delay`.
Murat65536 Sep 17, 2025
f43bac7
Rename `delay` parameter.
Murat65536 Sep 17, 2025
b37fda1
Remove `hasElapsed` `Frequency` overload.
Murat65536 Sep 17, 2025
06eb5d7
Rename `hasElapsed` parameter.
Murat65536 Sep 17, 2025
c0677ea
Remove `WatchDog` constructor.
Murat65536 Sep 17, 2025
2006b9e
Fix Lint and Format check.
Murat65536 Sep 18, 2025
414cbc4
Remove frequency overloads for debounce.
Murat65536 Sep 24, 2025
6b471ac
Add C++ constructors.
Murat65536 Sep 26, 2025
2958f61
Add some suggested changes.
Murat65536 Sep 29, 2025
6543a82
Simplify.
Murat65536 Sep 29, 2025
205246b
Small doc un-edit.
Murat65536 Sep 29, 2025
38e1802
Apply requested changes.
Murat65536 Oct 1, 2025
3c32461
Remove unused imports.
Murat65536 Oct 1, 2025
e604ba5
Remove unused import.
Murat65536 Oct 1, 2025
bb87fcc
Rearrange import.
Murat65536 Oct 1, 2025
cfdc1ed
Fix formatting.
Murat65536 Oct 1, 2025
b937642
Update wpilibc/src/main/native/include/frc/TimedRobot.h
Murat65536 Oct 1, 2025
3831527
Add overload for `StartPeriodic`.
Murat65536 Oct 1, 2025
f26103e
Merge branch 'unit-overloads' of https://github.com/Murat65536/allwpi…
Murat65536 Oct 1, 2025
13bc17e
Merge branch 'main' into unit-overloads
calcmogul Oct 3, 2025
d2fd7b7
Add suggested changes.
Murat65536 Oct 4, 2025
d9aa404
Update javadoc.
Murat65536 Oct 4, 2025
601e0a3
Reverted parameter name change.
Murat65536 Oct 5, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions wpilibc/src/main/native/cpp/TimedRobot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,8 @@ TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) {
HALUsageReporting::kFramework_Timed);
}

TimedRobot::TimedRobot(units::hertz_t frequency) : TimedRobot{1 / frequency} {}

TimedRobot::~TimedRobot() {
if (m_notifier != HAL_kInvalidHandle) {
int32_t status = 0;
Expand Down
8 changes: 8 additions & 0 deletions wpilibc/src/main/native/include/frc/TimedRobot.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@

#include <hal/Notifier.h>
#include <hal/Types.h>
#include <units/frequency.h>
#include <units/math.h>
#include <units/time.h>
#include <wpi/priority_queue.h>
Expand Down Expand Up @@ -51,6 +52,13 @@ class TimedRobot : public IterativeRobotBase {
*/
explicit TimedRobot(units::second_t period = kDefaultPeriod);

/**
* Constructor for TimedRobot.
*
* @param frequency Frequency.
*/
explicit TimedRobot(units::hertz_t frequency = 1 / kDefaultPeriod);

TimedRobot(TimedRobot&&) = default;
TimedRobot& operator=(TimedRobot&&) = default;

Expand Down
38 changes: 38 additions & 0 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,12 @@

package edu.wpi.first.wpilibj;

import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;

import edu.wpi.first.hal.NotifierJNI;
import edu.wpi.first.units.measure.Frequency;
import edu.wpi.first.units.measure.Time;
import java.util.concurrent.atomic.AtomicInteger;
import java.util.concurrent.locks.ReentrantLock;

Expand Down Expand Up @@ -186,6 +189,15 @@ public void startSingle(double delaySeconds) {
}
}

/**
* Run the callback once after the given delay.
*
* @param delay Time to wait before the callback is called.
*/
public void startSingle(Time delay) {
startSingle(delay.in(Seconds));
}

/**
* Run the callback periodically with the given period.
*
Expand All @@ -207,6 +219,32 @@ public void startPeriodic(double periodSeconds) {
}
}

/**
* Run the callback periodically with the given period.
*
* <p>The user-provided callback should be written so that it completes before the next time it's
* scheduled to run.
*
* @param period Period after which to call the callback starting one period after the call to
* this method.
*/
public void startPeriodic(Time period) {
startPeriodic(period.in(Seconds));
}

/**
* Run the callback periodically with the given frequency.
*
* <p>The user-provided callback should be written so that it completes before the next time it's
* scheduled to run.
*
* @param frequency Frequency at which to call the callback, starting one period after the call to
* this method.
*/
public void startPeriodic(Frequency frequency) {
startPeriodic(frequency.asPeriod());
}

/**
* Stop further callback invocations.
*
Expand Down
19 changes: 19 additions & 0 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import edu.wpi.first.hal.FRCNetComm.tResourceType;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.hal.NotifierJNI;
import edu.wpi.first.units.measure.Frequency;
import edu.wpi.first.units.measure.Time;
import java.util.PriorityQueue;

Expand Down Expand Up @@ -95,6 +96,24 @@ protected TimedRobot(double period) {
HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Timed);
}

/**
* Constructor for TimedRobot.
*
* @param period The period of the robot loop function.
*/
protected TimedRobot(Time period) {
this(period.in(Seconds));
}

/**
* Constructor for TimedRobot.
*
* @param frequency The frequency of the robot loop function.
*/
protected TimedRobot(Frequency frequency) {
this(frequency.asPeriod());
}

@Override
public void close() {
NotifierJNI.stopNotifier(m_notifier);
Expand Down
34 changes: 29 additions & 5 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,10 @@

package edu.wpi.first.wpilibj;

import static edu.wpi.first.units.Units.Seconds;

import edu.wpi.first.units.measure.Time;

/**
* A timer class.
*
Expand Down Expand Up @@ -46,10 +50,20 @@ public static double getMatchTime() {
}

/**
* Pause the thread for a specified time. Pause the execution of the thread for a specified period
* of time given in seconds. Motors will continue to run at their last assigned values, and
* sensors will continue to update. Only the task containing the wait will pause until the wait
* time is expired.
* Pause the execution of the thread for a specified period of time. Motors will continue to run
* at their last assigned values, and sensors will continue to update. Only the task containing
* the wait will pause until the wait time is expired.
*
* @param period Length of time to pause
*/
public static void delay(final Time period) {
delay(period.in(Seconds));
}

/**
* Pause the execution of the thread for a specified period of time given in seconds. Motors will
* continue to run at their last assigned values, and sensors will continue to update. Only the
* task containing the wait will pause until the wait time is expired.
*
* @param seconds Length of time to pause
*/
Expand Down Expand Up @@ -137,7 +151,17 @@ public void stop() {
/**
* Check if the period specified has passed.
*
* @param seconds The period to check.
* @param period The period to check.
* @return Whether the period has passed.
*/
public boolean hasElapsed(Time period) {
return hasElapsed(period.in(Seconds));
}

/**
* Check if the period specified has passed.
*
* @param seconds The period to check in seconds.
* @return Whether the period has passed.
*/
public boolean hasElapsed(double seconds) {
Expand Down
13 changes: 13 additions & 0 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,10 @@

package edu.wpi.first.wpilibj;

import static edu.wpi.first.units.Units.Seconds;

import edu.wpi.first.hal.NotifierJNI;
import edu.wpi.first.units.measure.Time;
import java.io.Closeable;
import java.util.PriorityQueue;
import java.util.concurrent.locks.ReentrantLock;
Expand Down Expand Up @@ -55,6 +58,16 @@ public Watchdog(double timeoutSeconds, Runnable callback) {
m_tracer = new Tracer();
}

/**
* Watchdog constructor.
*
* @param timeout The watchdog's timeout with microsecond resolution.
* @param callback This function is called when the timeout expires.
*/
public Watchdog(Time timeout, Runnable callback) {
this(timeout.in(Seconds), callback);
}

@Override
public void close() {
disable();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,11 @@

package edu.wpi.first.wpilibj.event;

import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;

import edu.wpi.first.math.filter.Debouncer;
import edu.wpi.first.units.measure.Time;
import java.util.concurrent.atomic.AtomicBoolean;
import java.util.function.BiFunction;
import java.util.function.BooleanSupplier;
Expand Down Expand Up @@ -167,7 +169,18 @@ public boolean getAsBoolean() {
* Creates a new debounced event from this event - it will become active when this event has been
* active for longer than the specified period.
*
* @param seconds The debounce period.
* @param period The debounce period.
* @return The debounced event (rising edges debounced only).
*/
public BooleanEvent debounce(Time period) {
return debounce(period.in(Seconds));
}

/**
* Creates a new debounced event from this event - it will become active when this event has been
* active for longer than the specified period.
*
* @param seconds The debounce period in seconds.
* @return The debounced event (rising edges debounced only).
*/
public BooleanEvent debounce(double seconds) {
Expand All @@ -178,7 +191,19 @@ public BooleanEvent debounce(double seconds) {
* Creates a new debounced event from this event - it will become active when this event has been
* active for longer than the specified period.
*
* @param seconds The debounce period.
* @param period The debounce period.
* @param type The debounce type.
* @return The debounced event.
*/
public BooleanEvent debounce(Time period, Debouncer.DebounceType type) {
return debounce(period.in(Seconds), type);
}

/**
* Creates a new debounced event from this event - it will become active when this event has been
* active for longer than the specified period.
*
* @param seconds The debounce period in seconds.
* @param type The debounce type.
* @return The debounced event.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,14 @@

package edu.wpi.first.wpilibj.smartdashboard;

import static edu.wpi.first.units.Units.Meters;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.networktables.NTSendable;
import edu.wpi.first.networktables.NTSendableBuilder;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.units.measure.Distance;
import edu.wpi.first.util.sendable.SendableRegistry;
import java.util.ArrayList;
import java.util.List;
Expand Down Expand Up @@ -66,6 +69,17 @@ public synchronized void setRobotPose(double xMeters, double yMeters, Rotation2d
m_objects.get(0).setPose(xMeters, yMeters, rotation);
}

/**
* Set the robot pose from x, y, and rotation.
*
* @param x X location
* @param y Y location
* @param rotation rotation
*/
public synchronized void setRobotPose(Distance x, Distance y, Rotation2d rotation) {
m_objects.get(0).setPose(x.in(Meters), y.in(Meters), rotation);
}

/**
* Get the robot pose.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,14 @@

package edu.wpi.first.wpilibj.smartdashboard;

import static edu.wpi.first.units.Units.Meters;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.networktables.DoubleArrayEntry;
import edu.wpi.first.units.measure.Distance;
import java.util.ArrayList;
import java.util.Collections;
import java.util.List;
Expand Down Expand Up @@ -51,6 +54,17 @@ public synchronized void setPose(double xMeters, double yMeters, Rotation2d rota
setPose(new Pose2d(xMeters, yMeters, rotation));
}

/**
* Set the pose from x, y, and rotation.
*
* @param x X location
* @param y Y location
* @param rotation rotation
*/
public synchronized void setPose(Distance x, Distance y, Rotation2d rotation) {
setPose(new Pose2d(x.in(Meters), y.in(Meters), rotation));
}

/**
* Get the pose.
*
Expand Down