mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
SCRIPT: Spotless Apply
This commit is contained in:
committed by
Peter Johnson
parent
c89910b7c6
commit
c48b722dac
@@ -6,13 +6,13 @@ package org.wpilib.drive;
|
||||
|
||||
import static org.wpilib.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import java.util.function.DoubleConsumer;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.motor.MotorController;
|
||||
import org.wpilib.math.util.MathUtil;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
import org.wpilib.hardware.motor.MotorController;
|
||||
import java.util.function.DoubleConsumer;
|
||||
|
||||
/**
|
||||
* A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive
|
||||
@@ -43,12 +43,13 @@ import java.util.function.DoubleConsumer;
|
||||
* positive Z axis points up. Rotations follow the right-hand rule, so counterclockwise rotation
|
||||
* around the Z axis is positive.
|
||||
*
|
||||
* <p>Inputs smaller then {@value org.wpilib.drive.RobotDriveBase#kDefaultDeadband} will
|
||||
* be set to 0, and larger values will be scaled so that the full range is still used. This deadband
|
||||
* value can be changed with {@link #setDeadband}.
|
||||
* <p>Inputs smaller then {@value org.wpilib.drive.RobotDriveBase#kDefaultDeadband} will be set to
|
||||
* 0, and larger values will be scaled so that the full range is still used. This deadband value can
|
||||
* be changed with {@link #setDeadband}.
|
||||
*
|
||||
* <p>{@link org.wpilib.hardware.motor.MotorSafety} is enabled by default. The tankDrive, arcadeDrive,
|
||||
* or curvatureDrive methods should be called periodically to avoid Motor Safety timeouts.
|
||||
* <p>{@link org.wpilib.hardware.motor.MotorSafety} is enabled by default. The tankDrive,
|
||||
* arcadeDrive, or curvatureDrive methods should be called periodically to avoid Motor Safety
|
||||
* timeouts.
|
||||
*/
|
||||
public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoCloseable {
|
||||
private static int instances;
|
||||
@@ -94,8 +95,8 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC
|
||||
* Construct a DifferentialDrive.
|
||||
*
|
||||
* <p>To pass multiple motors per side, use CAN motor controller followers or {@link
|
||||
* org.wpilib.hardware.motor.PWMMotorController#addFollower(PWMMotorController)}. If a
|
||||
* motor needs to be inverted, do so before passing it in.
|
||||
* org.wpilib.hardware.motor.PWMMotorController#addFollower(PWMMotorController)}. If a motor needs
|
||||
* to be inverted, do so before passing it in.
|
||||
*
|
||||
* @param leftMotor Left motor.
|
||||
* @param rightMotor Right motor.
|
||||
@@ -111,8 +112,8 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC
|
||||
* Construct a DifferentialDrive.
|
||||
*
|
||||
* <p>To pass multiple motors per side, use CAN motor controller followers or {@link
|
||||
* org.wpilib.hardware.motor.PWMMotorController#addFollower(PWMMotorController)}. If a
|
||||
* motor needs to be inverted, do so before passing it in.
|
||||
* org.wpilib.hardware.motor.PWMMotorController#addFollower(PWMMotorController)}. If a motor needs
|
||||
* to be inverted, do so before passing it in.
|
||||
*
|
||||
* @param leftMotor Left motor setter.
|
||||
* @param rightMotor Right motor setter.
|
||||
|
||||
@@ -6,15 +6,15 @@ package org.wpilib.drive;
|
||||
|
||||
import static org.wpilib.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import java.util.function.DoubleConsumer;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.math.util.MathUtil;
|
||||
import org.wpilib.hardware.motor.MotorController;
|
||||
import org.wpilib.math.geometry.Rotation2d;
|
||||
import org.wpilib.math.geometry.Translation2d;
|
||||
import org.wpilib.math.util.MathUtil;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
import org.wpilib.hardware.motor.MotorController;
|
||||
import java.util.function.DoubleConsumer;
|
||||
|
||||
/**
|
||||
* A class for driving Mecanum drive platforms.
|
||||
@@ -42,9 +42,9 @@ import java.util.function.DoubleConsumer;
|
||||
* positive Z axis points up. Rotations follow the right-hand rule, so counterclockwise rotation
|
||||
* around the Z axis is positive.
|
||||
*
|
||||
* <p>Inputs smaller then {@value org.wpilib.drive.RobotDriveBase#kDefaultDeadband} will
|
||||
* be set to 0, and larger values will be scaled so that the full range is still used. This deadband
|
||||
* value can be changed with {@link #setDeadband}.
|
||||
* <p>Inputs smaller then {@value org.wpilib.drive.RobotDriveBase#kDefaultDeadband} will be set to
|
||||
* 0, and larger values will be scaled so that the full range is still used. This deadband value can
|
||||
* be changed with {@link #setDeadband}.
|
||||
*
|
||||
* <p>{@link org.wpilib.hardware.motor.MotorSafety} is enabled by default. The driveCartesian or
|
||||
* drivePolar methods should be called periodically to avoid Motor Safety timeouts.
|
||||
|
||||
@@ -4,7 +4,6 @@
|
||||
|
||||
package org.wpilib.driverstation;
|
||||
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.hardware.hal.ControlWord;
|
||||
|
||||
/** A wrapper around Driver Station control word. */
|
||||
|
||||
@@ -4,6 +4,11 @@
|
||||
|
||||
package org.wpilib.driverstation;
|
||||
|
||||
import java.util.Map;
|
||||
import java.util.Optional;
|
||||
import java.util.OptionalDouble;
|
||||
import java.util.OptionalInt;
|
||||
import java.util.concurrent.locks.ReentrantLock;
|
||||
import org.wpilib.datalog.BooleanArrayLogEntry;
|
||||
import org.wpilib.datalog.BooleanLogEntry;
|
||||
import org.wpilib.datalog.DataLog;
|
||||
@@ -20,14 +25,9 @@ import org.wpilib.networktables.IntegerPublisher;
|
||||
import org.wpilib.networktables.NetworkTableInstance;
|
||||
import org.wpilib.networktables.StringPublisher;
|
||||
import org.wpilib.networktables.StringTopic;
|
||||
import org.wpilib.util.concurrent.EventVector;
|
||||
import org.wpilib.system.Timer;
|
||||
import org.wpilib.util.WPIUtilJNI;
|
||||
import java.util.Map;
|
||||
import java.util.Optional;
|
||||
import java.util.OptionalDouble;
|
||||
import java.util.OptionalInt;
|
||||
import java.util.concurrent.locks.ReentrantLock;
|
||||
import org.wpilib.util.concurrent.EventVector;
|
||||
|
||||
/** Provide access to the network communication data to / from the Driver Station. */
|
||||
public final class DriverStation {
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
|
||||
package org.wpilib.driverstation;
|
||||
|
||||
import org.wpilib.event.BooleanEvent;
|
||||
import org.wpilib.event.EventLoop;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.event.BooleanEvent;
|
||||
import org.wpilib.event.EventLoop;
|
||||
|
||||
/**
|
||||
* Handle input from Gamepad controllers connected to the Driver Station.
|
||||
|
||||
@@ -4,13 +4,13 @@
|
||||
|
||||
package org.wpilib.driverstation;
|
||||
|
||||
import org.wpilib.hardware.hal.DriverStationJNI;
|
||||
import org.wpilib.math.util.Pair;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.wpilib.driverstation.DriverStation.POVDirection;
|
||||
import org.wpilib.event.BooleanEvent;
|
||||
import org.wpilib.event.EventLoop;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.wpilib.hardware.hal.DriverStationJNI;
|
||||
import org.wpilib.math.util.Pair;
|
||||
|
||||
/**
|
||||
* Handle input from standard HID devices connected to the Driver Station.
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package org.wpilib.driverstation;
|
||||
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.event.BooleanEvent;
|
||||
import org.wpilib.event.EventLoop;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
|
||||
/**
|
||||
* Handle input from Flight Joysticks connected to the Driver Station.
|
||||
|
||||
@@ -7,11 +7,11 @@ package org.wpilib.event;
|
||||
import static org.wpilib.units.Units.Seconds;
|
||||
import static org.wpilib.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import org.wpilib.math.filter.Debouncer;
|
||||
import org.wpilib.units.measure.Time;
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import java.util.function.BiFunction;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import org.wpilib.math.filter.Debouncer;
|
||||
import org.wpilib.units.measure.Time;
|
||||
|
||||
/**
|
||||
* This class provides an easy way to link actions to active high logic signals. Each object
|
||||
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
package org.wpilib.hardware.accelerometer;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
import org.wpilib.hardware.bus.I2C;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.SimDevice;
|
||||
@@ -14,8 +16,6 @@ import org.wpilib.networktables.DoubleTopic;
|
||||
import org.wpilib.networktables.NTSendable;
|
||||
import org.wpilib.networktables.NTSendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
/** ADXL345 I2C Accelerometer. */
|
||||
@SuppressWarnings("TypeName")
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
|
||||
package org.wpilib.hardware.bus;
|
||||
|
||||
import java.io.Closeable;
|
||||
import org.wpilib.hardware.hal.CANAPIJNI;
|
||||
import org.wpilib.hardware.hal.CANAPITypes;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.can.CANReceiveMessage;
|
||||
import java.io.Closeable;
|
||||
|
||||
/**
|
||||
* High level class for interfacing with CAN devices conforming to the standard CAN spec.
|
||||
|
||||
@@ -6,10 +6,10 @@ package org.wpilib.hardware.bus;
|
||||
|
||||
import static org.wpilib.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.I2CJNI;
|
||||
import org.wpilib.hardware.hal.util.BoundaryException;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
/**
|
||||
* I2C bus interface class.
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package org.wpilib.hardware.bus;
|
||||
|
||||
import java.nio.charset.StandardCharsets;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.SerialPortJNI;
|
||||
import java.nio.charset.StandardCharsets;
|
||||
|
||||
/** Driver for the serial ports (USB, MXP, Onboard) on the roboRIO. */
|
||||
public class SerialPort implements AutoCloseable {
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package org.wpilib.hardware.discrete;
|
||||
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import org.wpilib.hardware.hal.DIOJNI;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.SimDevice;
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package org.wpilib.hardware.discrete;
|
||||
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import org.wpilib.hardware.hal.DIOJNI;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.SimDevice;
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package org.wpilib.hardware.discrete;
|
||||
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.PWMJNI;
|
||||
import org.wpilib.hardware.hal.SimDevice;
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
|
||||
@@ -9,6 +9,10 @@ import static org.wpilib.units.Units.Microsecond;
|
||||
import static org.wpilib.units.Units.Microseconds;
|
||||
import static org.wpilib.units.Units.Value;
|
||||
|
||||
import java.util.Map;
|
||||
import java.util.Objects;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.function.DoubleSupplier;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.system.RobotController;
|
||||
import org.wpilib.units.collections.LongToObjectHashMap;
|
||||
@@ -17,12 +21,8 @@ import org.wpilib.units.measure.Distance;
|
||||
import org.wpilib.units.measure.Frequency;
|
||||
import org.wpilib.units.measure.LinearVelocity;
|
||||
import org.wpilib.units.measure.Time;
|
||||
import org.wpilib.util.WPIUtilJNI;
|
||||
import org.wpilib.util.Color;
|
||||
import java.util.Map;
|
||||
import java.util.Objects;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.function.DoubleSupplier;
|
||||
import org.wpilib.util.WPIUtilJNI;
|
||||
|
||||
/**
|
||||
* An LED pattern controls lights on an LED strip to command patterns of color that may change over
|
||||
|
||||
@@ -6,8 +6,8 @@ package org.wpilib.hardware.motor;
|
||||
|
||||
import static org.wpilib.units.Units.Volts;
|
||||
|
||||
import org.wpilib.units.measure.Voltage;
|
||||
import org.wpilib.system.RobotController;
|
||||
import org.wpilib.units.measure.Voltage;
|
||||
|
||||
/** Interface for motor controlling devices. */
|
||||
public interface MotorController {
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package org.wpilib.hardware.motor;
|
||||
|
||||
import java.util.Arrays;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
import java.util.Arrays;
|
||||
|
||||
/**
|
||||
* Allows multiple {@link MotorController} objects to be linked together.
|
||||
|
||||
@@ -4,14 +4,14 @@
|
||||
|
||||
package org.wpilib.hardware.motor;
|
||||
|
||||
import java.util.LinkedHashSet;
|
||||
import java.util.Set;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.hardware.hal.ControlWord;
|
||||
import org.wpilib.hardware.hal.DriverStationJNI;
|
||||
import org.wpilib.opmode.RobotState;
|
||||
import org.wpilib.system.Timer;
|
||||
import org.wpilib.util.WPIUtilJNI;
|
||||
import java.util.LinkedHashSet;
|
||||
import java.util.Set;
|
||||
|
||||
/**
|
||||
* The Motor Safety feature acts as a watchdog timer for an individual motor. It operates by
|
||||
|
||||
@@ -4,16 +4,15 @@
|
||||
|
||||
package org.wpilib.hardware.motor;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import org.wpilib.hardware.discrete.PWM;
|
||||
import org.wpilib.hardware.hal.SimDevice;
|
||||
import org.wpilib.hardware.hal.SimDevice.Direction;
|
||||
import org.wpilib.hardware.hal.SimDouble;
|
||||
import org.wpilib.system.RobotController;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
import org.wpilib.hardware.motor.MotorSafety;
|
||||
import org.wpilib.hardware.discrete.PWM;
|
||||
import org.wpilib.system.RobotController;
|
||||
import java.util.ArrayList;
|
||||
|
||||
/** Common base class for all PWM Motor Controllers. */
|
||||
@SuppressWarnings("removal")
|
||||
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package org.wpilib.hardware.pneumatic;
|
||||
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.PortsJNI;
|
||||
import org.wpilib.hardware.hal.REVPHFaults;
|
||||
import org.wpilib.hardware.hal.REVPHJNI;
|
||||
import org.wpilib.hardware.hal.REVPHStickyFaults;
|
||||
import org.wpilib.hardware.hal.REVPHVersion;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.wpilib.system.SensorUtil;
|
||||
|
||||
/** Module class for controlling a REV Robotics Pneumatic Hub. */
|
||||
public class PneumaticHub implements PneumaticsBase {
|
||||
|
||||
@@ -4,12 +4,12 @@
|
||||
|
||||
package org.wpilib.hardware.pneumatic;
|
||||
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.wpilib.hardware.hal.CTREPCMJNI;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.PortsJNI;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.wpilib.system.SensorUtil;
|
||||
|
||||
/** Module class for controlling a Cross The Road Electronics Pneumatics Control Module. */
|
||||
public class PneumaticsControlModule implements PneumaticsBase {
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package org.wpilib.internal;
|
||||
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.hardware.hal.DriverStationJNI;
|
||||
import org.wpilib.util.WPIUtilJNI;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
|
||||
/** For internal use only. */
|
||||
public class DriverStationModeThread implements AutoCloseable {
|
||||
|
||||
@@ -4,10 +4,8 @@
|
||||
|
||||
package org.wpilib.opmode;
|
||||
|
||||
import org.wpilib.vision.stream.CameraServerShared;
|
||||
import org.wpilib.vision.stream.CameraServerSharedStore;
|
||||
import org.wpilib.system.Notifier;
|
||||
import org.wpilib.system.RuntimeType;
|
||||
import java.util.concurrent.locks.ReentrantLock;
|
||||
import java.util.function.Supplier;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.HALUtil;
|
||||
@@ -16,11 +14,13 @@ import org.wpilib.math.util.MathSharedStore;
|
||||
import org.wpilib.networktables.MultiSubscriber;
|
||||
import org.wpilib.networktables.NetworkTableEvent;
|
||||
import org.wpilib.networktables.NetworkTableInstance;
|
||||
import org.wpilib.system.Notifier;
|
||||
import org.wpilib.system.RuntimeType;
|
||||
import org.wpilib.system.Timer;
|
||||
import org.wpilib.util.WPIUtilJNI;
|
||||
import org.wpilib.system.WPILibVersion;
|
||||
import java.util.concurrent.locks.ReentrantLock;
|
||||
import java.util.function.Supplier;
|
||||
import org.wpilib.util.WPIUtilJNI;
|
||||
import org.wpilib.vision.stream.CameraServerShared;
|
||||
import org.wpilib.vision.stream.CameraServerSharedStore;
|
||||
|
||||
/**
|
||||
* Implement a Robot Program framework. The RobotBase class is intended to be subclassed to create a
|
||||
|
||||
@@ -6,13 +6,13 @@ package org.wpilib.opmode;
|
||||
|
||||
import static org.wpilib.units.Units.Seconds;
|
||||
|
||||
import java.util.PriorityQueue;
|
||||
import org.wpilib.hardware.hal.DriverStationJNI;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.NotifierJNI;
|
||||
import org.wpilib.system.RobotController;
|
||||
import org.wpilib.units.measure.Frequency;
|
||||
import org.wpilib.units.measure.Time;
|
||||
import java.util.PriorityQueue;
|
||||
|
||||
/**
|
||||
* TimedRobot implements the IterativeRobotBase robot program framework.
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package org.wpilib.simulation;
|
||||
|
||||
import org.wpilib.hardware.hal.SimDouble;
|
||||
import org.wpilib.hardware.accelerometer.ADXL345_I2C;
|
||||
import java.util.Objects;
|
||||
import org.wpilib.hardware.accelerometer.ADXL345_I2C;
|
||||
import org.wpilib.hardware.hal.SimDouble;
|
||||
|
||||
/** Class to control a simulated ADXL345. */
|
||||
public class ADXL345Sim {
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package org.wpilib.simulation;
|
||||
|
||||
import org.wpilib.hardware.discrete.AnalogInput;
|
||||
import org.wpilib.hardware.hal.simulation.AnalogInDataJNI;
|
||||
import org.wpilib.hardware.hal.simulation.NotifyCallback;
|
||||
import org.wpilib.hardware.discrete.AnalogInput;
|
||||
|
||||
/** Class to control a simulated analog input. */
|
||||
public class AnalogInputSim {
|
||||
|
||||
@@ -33,8 +33,8 @@ public final class BatterySim {
|
||||
/**
|
||||
* Calculate the loaded battery voltage. Use this with {@link RoboRioSim#setVInVoltage(double)} to
|
||||
* set the simulated battery voltage, which can then be retrieved with the {@link
|
||||
* org.wpilib.system.RobotController#getBatteryVoltage()} method. This function assumes a
|
||||
* nominal voltage of 12v and a resistance of 20 milliohms (0.020 ohms)
|
||||
* org.wpilib.system.RobotController#getBatteryVoltage()} method. This function assumes a nominal
|
||||
* voltage of 12v and a resistance of 20 milliohms (0.020 ohms)
|
||||
*
|
||||
* @param currents The currents drawn from the battery.
|
||||
* @return The battery's voltage under load.
|
||||
|
||||
@@ -27,10 +27,9 @@ public class DCMotorSim extends LinearSystemSim<N2, N1, N2> {
|
||||
*
|
||||
* @param plant The linear system representing the DC motor. This system can be created with
|
||||
* {@link org.wpilib.math.system.plant.LinearSystemId#createDCMotorSystem(DCMotor, double,
|
||||
* double)} or {@link
|
||||
* org.wpilib.math.system.plant.LinearSystemId#createDCMotorSystem(double, double)}. If
|
||||
* {@link org.wpilib.math.system.plant.LinearSystemId#createDCMotorSystem(double, double)}
|
||||
* is used, the distance unit must be radians.
|
||||
* double)} or {@link org.wpilib.math.system.plant.LinearSystemId#createDCMotorSystem(double,
|
||||
* double)}. If {@link org.wpilib.math.system.plant.LinearSystemId#createDCMotorSystem(double,
|
||||
* double)} is used, the distance unit must be radians.
|
||||
* @param gearbox The type of and number of motors in the DC motor gearbox.
|
||||
* @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no
|
||||
* noise is desired. If present must have 2 elements. The first element is for position. The
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package org.wpilib.simulation;
|
||||
|
||||
import org.wpilib.hardware.hal.simulation.DIODataJNI;
|
||||
import org.wpilib.hardware.hal.simulation.NotifyCallback;
|
||||
import org.wpilib.hardware.discrete.DigitalInput;
|
||||
import org.wpilib.hardware.discrete.DigitalOutput;
|
||||
import org.wpilib.hardware.hal.simulation.DIODataJNI;
|
||||
import org.wpilib.hardware.hal.simulation.NotifyCallback;
|
||||
|
||||
/** Class to control a simulated digital input or output. */
|
||||
public class DIOSim {
|
||||
|
||||
@@ -4,12 +4,10 @@
|
||||
|
||||
package org.wpilib.simulation;
|
||||
|
||||
import org.wpilib.math.linalg.Matrix;
|
||||
import org.wpilib.math.util.Nat;
|
||||
import org.wpilib.math.util.StateSpaceUtil;
|
||||
import org.wpilib.math.linalg.VecBuilder;
|
||||
import org.wpilib.math.geometry.Pose2d;
|
||||
import org.wpilib.math.geometry.Rotation2d;
|
||||
import org.wpilib.math.linalg.Matrix;
|
||||
import org.wpilib.math.linalg.VecBuilder;
|
||||
import org.wpilib.math.numbers.N1;
|
||||
import org.wpilib.math.numbers.N2;
|
||||
import org.wpilib.math.numbers.N7;
|
||||
@@ -17,6 +15,8 @@ import org.wpilib.math.system.LinearSystem;
|
||||
import org.wpilib.math.system.NumericalIntegration;
|
||||
import org.wpilib.math.system.plant.DCMotor;
|
||||
import org.wpilib.math.system.plant.LinearSystemId;
|
||||
import org.wpilib.math.util.Nat;
|
||||
import org.wpilib.math.util.StateSpaceUtil;
|
||||
import org.wpilib.math.util.Units;
|
||||
import org.wpilib.system.RobotController;
|
||||
|
||||
@@ -24,8 +24,8 @@ import org.wpilib.system.RobotController;
|
||||
* This class simulates the state of the drivetrain. In simulationPeriodic, users should first set
|
||||
* inputs from motors with {@link #setInputs(double, double)}, call {@link #update(double)} to
|
||||
* update the simulation, and set estimated encoder and gyro positions, as well as estimated
|
||||
* odometry pose. Teams can use {@link org.wpilib.smartdashboard.Field2d} to visualize
|
||||
* their robot on the Sim GUI's field.
|
||||
* odometry pose. Teams can use {@link org.wpilib.smartdashboard.Field2d} to visualize their robot
|
||||
* on the Sim GUI's field.
|
||||
*
|
||||
* <p>Our state-space system is:
|
||||
*
|
||||
@@ -90,8 +90,8 @@ public class DifferentialDrivetrainSim {
|
||||
*
|
||||
* @param plant The {@link LinearSystem} representing the robot's drivetrain. This system can be
|
||||
* created with {@link
|
||||
* org.wpilib.math.system.plant.LinearSystemId#createDrivetrainVelocitySystem(DCMotor,
|
||||
* double, double, double, double, double)} or {@link
|
||||
* org.wpilib.math.system.plant.LinearSystemId#createDrivetrainVelocitySystem(DCMotor, double,
|
||||
* double, double, double, double)} or {@link
|
||||
* org.wpilib.math.system.plant.LinearSystemId#identifyDrivetrainSystem(double, double,
|
||||
* double, double)}.
|
||||
* @param driveMotor A {@link DCMotor} representing the drivetrain.
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package org.wpilib.simulation;
|
||||
|
||||
import java.util.NoSuchElementException;
|
||||
import org.wpilib.hardware.discrete.DigitalOutput;
|
||||
import org.wpilib.hardware.hal.simulation.DigitalPWMDataJNI;
|
||||
import org.wpilib.hardware.hal.simulation.NotifyCallback;
|
||||
import org.wpilib.hardware.discrete.DigitalOutput;
|
||||
import java.util.NoSuchElementException;
|
||||
|
||||
/**
|
||||
* Class to control a simulated digital PWM output.
|
||||
|
||||
@@ -4,12 +4,12 @@
|
||||
|
||||
package org.wpilib.simulation;
|
||||
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.hardware.hal.AllianceStationID;
|
||||
import org.wpilib.hardware.hal.DriverStationJNI;
|
||||
import org.wpilib.hardware.hal.simulation.DriverStationDataJNI;
|
||||
import org.wpilib.hardware.hal.simulation.NotifyCallback;
|
||||
import org.wpilib.util.WPIUtilJNI;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
|
||||
/** Class to control a simulated driver station. */
|
||||
public final class DriverStationSim {
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package org.wpilib.simulation;
|
||||
|
||||
import java.util.NoSuchElementException;
|
||||
import org.wpilib.hardware.hal.simulation.EncoderDataJNI;
|
||||
import org.wpilib.hardware.hal.simulation.NotifyCallback;
|
||||
import org.wpilib.hardware.rotation.Encoder;
|
||||
import java.util.NoSuchElementException;
|
||||
|
||||
/** Class to control a simulated encoder. */
|
||||
public class EncoderSim {
|
||||
|
||||
@@ -4,13 +4,13 @@
|
||||
|
||||
package org.wpilib.simulation;
|
||||
|
||||
import org.wpilib.math.linalg.Matrix;
|
||||
import org.wpilib.math.util.Num;
|
||||
import org.wpilib.math.util.StateSpaceUtil;
|
||||
import org.wpilib.math.numbers.N1;
|
||||
import org.wpilib.math.system.LinearSystem;
|
||||
import org.ejml.MatrixDimensionException;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
import org.wpilib.math.linalg.Matrix;
|
||||
import org.wpilib.math.numbers.N1;
|
||||
import org.wpilib.math.system.LinearSystem;
|
||||
import org.wpilib.math.util.Num;
|
||||
import org.wpilib.math.util.StateSpaceUtil;
|
||||
|
||||
/**
|
||||
* This class helps simulate linear systems. To use this class, do the following in the {@link
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package org.wpilib.simulation;
|
||||
|
||||
import org.wpilib.hardware.discrete.PWM;
|
||||
import org.wpilib.hardware.hal.simulation.NotifyCallback;
|
||||
import org.wpilib.hardware.hal.simulation.PWMDataJNI;
|
||||
import org.wpilib.hardware.discrete.PWM;
|
||||
|
||||
/** Class to control a simulated PWM output. */
|
||||
public class PWMSim {
|
||||
|
||||
@@ -235,7 +235,8 @@ public class SimDeviceSim {
|
||||
}
|
||||
|
||||
/**
|
||||
* Register a callback to be run every time a new {@link org.wpilib.hardware.hal.SimDevice} is created.
|
||||
* Register a callback to be run every time a new {@link org.wpilib.hardware.hal.SimDevice} is
|
||||
* created.
|
||||
*
|
||||
* @param prefix the prefix to filter sim devices
|
||||
* @param callback the callback
|
||||
|
||||
@@ -38,8 +38,8 @@ public class SingleJointedArmSim extends LinearSystemSim<N2, N1, N2> {
|
||||
* Creates a simulated arm mechanism.
|
||||
*
|
||||
* @param plant The linear system that represents the arm. This system can be created with {@link
|
||||
* org.wpilib.math.system.plant.LinearSystemId#createSingleJointedArmSystem(DCMotor,
|
||||
* double, double)}.
|
||||
* org.wpilib.math.system.plant.LinearSystemId#createSingleJointedArmSystem(DCMotor, double,
|
||||
* double)}.
|
||||
* @param gearbox The type of and number of motors in the arm gearbox.
|
||||
* @param gearing The gearing of the arm (numbers greater than 1 represent reductions).
|
||||
* @param armLength The length of the arm in meters.
|
||||
|
||||
@@ -6,6 +6,8 @@ package org.wpilib.smartdashboard;
|
||||
|
||||
import static org.wpilib.units.Units.Meters;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import org.wpilib.math.geometry.Pose2d;
|
||||
import org.wpilib.math.geometry.Rotation2d;
|
||||
import org.wpilib.networktables.NTSendable;
|
||||
@@ -13,8 +15,6 @@ import org.wpilib.networktables.NTSendableBuilder;
|
||||
import org.wpilib.networktables.NetworkTable;
|
||||
import org.wpilib.units.measure.Distance;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
/**
|
||||
* 2D representation of game field for dashboards.
|
||||
|
||||
@@ -6,15 +6,15 @@ package org.wpilib.smartdashboard;
|
||||
|
||||
import static org.wpilib.units.Units.Meters;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.Collections;
|
||||
import java.util.List;
|
||||
import org.wpilib.math.geometry.Pose2d;
|
||||
import org.wpilib.math.geometry.Rotation2d;
|
||||
import org.wpilib.math.geometry.Translation2d;
|
||||
import org.wpilib.math.trajectory.Trajectory;
|
||||
import org.wpilib.networktables.DoubleArrayEntry;
|
||||
import org.wpilib.units.measure.Distance;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Collections;
|
||||
import java.util.List;
|
||||
|
||||
/** Game field object on a Field2d. */
|
||||
public class FieldObject2d implements AutoCloseable {
|
||||
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package org.wpilib.smartdashboard;
|
||||
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import java.util.Map.Entry;
|
||||
import org.wpilib.networktables.DoubleArrayPublisher;
|
||||
import org.wpilib.networktables.NTSendable;
|
||||
import org.wpilib.networktables.NTSendableBuilder;
|
||||
import org.wpilib.networktables.NetworkTable;
|
||||
import org.wpilib.networktables.StringPublisher;
|
||||
import org.wpilib.util.Color8Bit;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import java.util.Map.Entry;
|
||||
|
||||
/**
|
||||
* Visual 2D representation of arms, elevators, and general mechanisms through a node-based API.
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package org.wpilib.smartdashboard;
|
||||
|
||||
import org.wpilib.networktables.NetworkTable;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.wpilib.networktables.NetworkTable;
|
||||
|
||||
/**
|
||||
* Common base class for all Mechanism2d node types.
|
||||
|
||||
@@ -4,6 +4,15 @@
|
||||
|
||||
package org.wpilib.smartdashboard;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.function.Consumer;
|
||||
import java.util.function.DoubleConsumer;
|
||||
import java.util.function.DoubleSupplier;
|
||||
import java.util.function.LongConsumer;
|
||||
import java.util.function.LongSupplier;
|
||||
import java.util.function.Supplier;
|
||||
import org.wpilib.networktables.BooleanArrayPublisher;
|
||||
import org.wpilib.networktables.BooleanArraySubscriber;
|
||||
import org.wpilib.networktables.BooleanArrayTopic;
|
||||
@@ -43,19 +52,10 @@ import org.wpilib.networktables.StringSubscriber;
|
||||
import org.wpilib.networktables.StringTopic;
|
||||
import org.wpilib.networktables.Subscriber;
|
||||
import org.wpilib.networktables.Topic;
|
||||
import org.wpilib.system.RobotController;
|
||||
import org.wpilib.util.function.BooleanConsumer;
|
||||
import org.wpilib.util.function.FloatConsumer;
|
||||
import org.wpilib.util.function.FloatSupplier;
|
||||
import org.wpilib.system.RobotController;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.function.Consumer;
|
||||
import java.util.function.DoubleConsumer;
|
||||
import java.util.function.DoubleSupplier;
|
||||
import java.util.function.LongConsumer;
|
||||
import java.util.function.LongSupplier;
|
||||
import java.util.function.Supplier;
|
||||
|
||||
/** Implementation detail for SendableBuilder. */
|
||||
public class SendableBuilderImpl implements NTSendableBuilder {
|
||||
|
||||
@@ -6,14 +6,14 @@ package org.wpilib.smartdashboard;
|
||||
|
||||
import static org.wpilib.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
import java.util.LinkedHashMap;
|
||||
import java.util.Map;
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import java.util.concurrent.locks.ReentrantLock;
|
||||
import java.util.function.Consumer;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
|
||||
/**
|
||||
* The {@link SendableChooser} class is a useful tool for presenting a selection of options to the
|
||||
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package org.wpilib.smartdashboard;
|
||||
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import java.util.Set;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.networktables.NetworkTable;
|
||||
import org.wpilib.networktables.NetworkTableEntry;
|
||||
import org.wpilib.networktables.NetworkTableInstance;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import java.util.Set;
|
||||
|
||||
/**
|
||||
* The {@link SmartDashboard} class is the bridge between robot programs and the SmartDashboard on
|
||||
|
||||
@@ -12,8 +12,11 @@ import static org.wpilib.units.Units.RotationsPerSecond;
|
||||
import static org.wpilib.units.Units.Second;
|
||||
import static org.wpilib.units.Units.Volts;
|
||||
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.wpilib.datalog.DoubleLogEntry;
|
||||
import org.wpilib.datalog.StringLogEntry;
|
||||
import org.wpilib.system.DataLogManager;
|
||||
import org.wpilib.units.measure.Angle;
|
||||
import org.wpilib.units.measure.AngularAcceleration;
|
||||
import org.wpilib.units.measure.AngularVelocity;
|
||||
@@ -22,9 +25,6 @@ import org.wpilib.units.measure.Distance;
|
||||
import org.wpilib.units.measure.LinearAcceleration;
|
||||
import org.wpilib.units.measure.LinearVelocity;
|
||||
import org.wpilib.units.measure.Voltage;
|
||||
import org.wpilib.system.DataLogManager;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
|
||||
/**
|
||||
* Utility for logging data from a SysId test routine. Each complete routine (quasistatic and
|
||||
|
||||
@@ -4,17 +4,6 @@
|
||||
|
||||
package org.wpilib.system;
|
||||
|
||||
import org.wpilib.datalog.DataLog;
|
||||
import org.wpilib.datalog.DataLogBackgroundWriter;
|
||||
import org.wpilib.datalog.FileLogger;
|
||||
import org.wpilib.datalog.IntegerLogEntry;
|
||||
import org.wpilib.datalog.StringLogEntry;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.networktables.NetworkTableInstance;
|
||||
import org.wpilib.opmode.RobotBase;
|
||||
import org.wpilib.util.WPIUtilJNI;
|
||||
import org.wpilib.util.concurrent.Event;
|
||||
import java.io.File;
|
||||
import java.io.IOException;
|
||||
import java.nio.file.Files;
|
||||
@@ -26,6 +15,17 @@ import java.time.format.DateTimeFormatter;
|
||||
import java.util.Arrays;
|
||||
import java.util.Comparator;
|
||||
import java.util.Random;
|
||||
import org.wpilib.datalog.DataLog;
|
||||
import org.wpilib.datalog.DataLogBackgroundWriter;
|
||||
import org.wpilib.datalog.FileLogger;
|
||||
import org.wpilib.datalog.IntegerLogEntry;
|
||||
import org.wpilib.datalog.StringLogEntry;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.networktables.NetworkTableInstance;
|
||||
import org.wpilib.opmode.RobotBase;
|
||||
import org.wpilib.util.WPIUtilJNI;
|
||||
import org.wpilib.util.concurrent.Event;
|
||||
|
||||
/**
|
||||
* Centralized data log that provides automatic data log file management. It automatically cleans up
|
||||
|
||||
@@ -7,13 +7,12 @@ package org.wpilib.system;
|
||||
import static org.wpilib.units.Units.Seconds;
|
||||
import static org.wpilib.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import java.util.concurrent.locks.ReentrantLock;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.hardware.hal.NotifierJNI;
|
||||
import org.wpilib.units.measure.Frequency;
|
||||
import org.wpilib.units.measure.Time;
|
||||
import org.wpilib.system.RobotController;
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import java.util.concurrent.locks.ReentrantLock;
|
||||
|
||||
/**
|
||||
* Notifiers run a user-provided callback function on a separate thread.
|
||||
|
||||
@@ -9,6 +9,7 @@ import static org.wpilib.units.Units.Celsius;
|
||||
import static org.wpilib.units.Units.Microseconds;
|
||||
import static org.wpilib.units.Units.Volts;
|
||||
|
||||
import java.util.function.LongSupplier;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.HALUtil;
|
||||
import org.wpilib.hardware.hal.PowerJNI;
|
||||
@@ -18,7 +19,6 @@ import org.wpilib.units.measure.Current;
|
||||
import org.wpilib.units.measure.Temperature;
|
||||
import org.wpilib.units.measure.Time;
|
||||
import org.wpilib.units.measure.Voltage;
|
||||
import java.util.function.LongSupplier;
|
||||
|
||||
/** Contains functions for roboRIO functionality. */
|
||||
public final class RobotController {
|
||||
|
||||
@@ -6,8 +6,8 @@ package org.wpilib.system;
|
||||
|
||||
import static org.wpilib.units.Units.Seconds;
|
||||
|
||||
import org.wpilib.units.measure.Time;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.units.measure.Time;
|
||||
|
||||
/**
|
||||
* A timer class.
|
||||
|
||||
@@ -6,12 +6,12 @@ package org.wpilib.system;
|
||||
|
||||
import static org.wpilib.units.Units.Seconds;
|
||||
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.hardware.hal.NotifierJNI;
|
||||
import org.wpilib.units.measure.Time;
|
||||
import java.io.Closeable;
|
||||
import java.util.PriorityQueue;
|
||||
import java.util.concurrent.locks.ReentrantLock;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
import org.wpilib.hardware.hal.NotifierJNI;
|
||||
import org.wpilib.units.measure.Time;
|
||||
|
||||
/**
|
||||
* A class that's a wrapper around a watchdog timer.
|
||||
|
||||
@@ -4,23 +4,23 @@
|
||||
|
||||
package org.wpilib.util;
|
||||
|
||||
import org.wpilib.system.RobotController;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.smartdashboard.SmartDashboard;
|
||||
import java.util.Comparator;
|
||||
import java.util.EnumMap;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import java.util.Set;
|
||||
import java.util.TreeSet;
|
||||
import org.wpilib.smartdashboard.SmartDashboard;
|
||||
import org.wpilib.system.RobotController;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
|
||||
/**
|
||||
* Persistent alert to be sent via NetworkTables. Alerts are tagged with a type of {@code kError},
|
||||
* {@code kWarning}, or {@code kInfo} to denote urgency. See {@link
|
||||
* org.wpilib.util.Alert.AlertType AlertType} for suggested usage of each type. Alerts can be
|
||||
* displayed on supported dashboards, and are shown in a priority order based on type and recency of
|
||||
* activation, with newly activated alerts first.
|
||||
* {@code kWarning}, or {@code kInfo} to denote urgency. See {@link org.wpilib.util.Alert.AlertType
|
||||
* AlertType} for suggested usage of each type. Alerts can be displayed on supported dashboards, and
|
||||
* are shown in a priority order based on type and recency of activation, with newly activated
|
||||
* alerts first.
|
||||
*
|
||||
* <p>Alerts should be created once and stored persistently, then updated to "active" or "inactive"
|
||||
* as necessary. {@link #set(boolean)} can be safely called periodically.
|
||||
|
||||
@@ -4,8 +4,8 @@
|
||||
|
||||
package org.wpilib.util;
|
||||
|
||||
import org.wpilib.math.util.MathUtil;
|
||||
import java.util.Objects;
|
||||
import org.wpilib.math.util.MathUtil;
|
||||
|
||||
/**
|
||||
* Represents colors.
|
||||
|
||||
@@ -6,6 +6,8 @@ package org.wpilib.util;
|
||||
|
||||
import static org.wpilib.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import java.util.Collection;
|
||||
import java.util.EnumSet;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.networktables.MultiSubscriber;
|
||||
import org.wpilib.networktables.NetworkTable;
|
||||
@@ -16,8 +18,6 @@ import org.wpilib.networktables.NetworkTableListener;
|
||||
import org.wpilib.networktables.StringPublisher;
|
||||
import org.wpilib.networktables.StringTopic;
|
||||
import org.wpilib.networktables.Topic;
|
||||
import java.util.Collection;
|
||||
import java.util.EnumSet;
|
||||
|
||||
/**
|
||||
* The preferences class provides a relatively simple way to save important values to the roboRIO to
|
||||
|
||||
Reference in New Issue
Block a user