mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Merge branch 'main' into 2027
This commit is contained in:
@@ -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;
|
||||
|
||||
@@ -186,6 +189,15 @@ public class Notifier implements AutoCloseable {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* 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.
|
||||
*
|
||||
@@ -207,6 +219,32 @@ public class Notifier implements AutoCloseable {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* 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.
|
||||
*
|
||||
|
||||
@@ -9,6 +9,7 @@ import static edu.wpi.first.units.Units.Seconds;
|
||||
import edu.wpi.first.hal.DriverStationJNI;
|
||||
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;
|
||||
|
||||
@@ -82,7 +83,7 @@ public class TimedRobot extends IterativeRobotBase {
|
||||
/**
|
||||
* Constructor for TimedRobot.
|
||||
*
|
||||
* @param period Period in seconds.
|
||||
* @param period The period of the robot loop function.
|
||||
*/
|
||||
protected TimedRobot(double period) {
|
||||
super(period);
|
||||
@@ -93,6 +94,24 @@ public class TimedRobot extends IterativeRobotBase {
|
||||
HAL.reportUsage("Framework", "TimedRobot");
|
||||
}
|
||||
|
||||
/**
|
||||
* 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);
|
||||
|
||||
@@ -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.
|
||||
*
|
||||
@@ -46,10 +50,20 @@ public class Timer {
|
||||
}
|
||||
|
||||
/**
|
||||
* 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
|
||||
*/
|
||||
@@ -137,7 +151,17 @@ public class Timer {
|
||||
/**
|
||||
* 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) {
|
||||
|
||||
@@ -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;
|
||||
@@ -55,6 +58,16 @@ public class Watchdog implements Closeable, Comparable<Watchdog> {
|
||||
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();
|
||||
|
||||
@@ -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;
|
||||
@@ -167,7 +169,18 @@ public class BooleanEvent implements BooleanSupplier {
|
||||
* 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) {
|
||||
@@ -178,7 +191,19 @@ public class BooleanEvent implements BooleanSupplier {
|
||||
* 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.
|
||||
*/
|
||||
|
||||
@@ -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;
|
||||
@@ -66,6 +69,17 @@ public class Field2d implements NTSendable, AutoCloseable {
|
||||
m_objects.get(0).setPose(x, y, 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.
|
||||
*
|
||||
|
||||
@@ -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;
|
||||
@@ -51,6 +54,17 @@ public class FieldObject2d implements AutoCloseable {
|
||||
setPose(new Pose2d(x, y, 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.
|
||||
*
|
||||
|
||||
Reference in New Issue
Block a user