diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PIDController.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PIDController.java index fd3838e2f7..2dcfc1496b 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PIDController.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PIDController.java @@ -372,10 +372,10 @@ public class PIDController implements LiveWindowSendable, Controller { } /** - * Sets the maximum and minimum values expected from the input. + * Sets the maximum and minimum values expected from the input and setpoint. * - * @param minimumInput the minimum percentage expected from the input - * @param maximumInput the maximum percentage expected from the output + * @param minimumInput the minimum value expected from the input + * @param maximumInput the maximum value expected from the input */ public synchronized void setInputRange(double minimumInput, double maximumInput) { if (minimumInput > maximumInput) { @@ -442,7 +442,7 @@ public class PIDController implements LiveWindowSendable, Controller { * Set the percentage error which is considered tolerable for use with * OnTarget. (Input of 15.0 = 15 percent) * @param percent error which is tolerable - * @deprecated Use {@link #setPercentTolerance(double) or {@link #setAbsoluteTolerance(double)} instead. + * @deprecated Use {@link #setPercentTolerance(double)} or {@link #setAbsoluteTolerance(double)} instead. */ @Deprecated public synchronized void setTolerance(double percent) { diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java index 158fd58961..4801157e67 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java @@ -95,11 +95,7 @@ public abstract class PIDCommand extends Command implements Sendable { /** * Returns the {@link PIDController} used by this {@link PIDCommand}. * Use this if you would like to fine tune the pid loop. - * - *

Notice that calling {@link PIDController#setSetpoint(double) setSetpoint(...)} on the controller - * will not result in the setpoint being trimmed to be in - * the range defined by {@link PIDCommand#setSetpointRange(double, double) setSetpointRange(...)}.

- * + * * @return the {@link PIDController} used by this {@link PIDCommand} */ protected PIDController getPIDController() { @@ -120,7 +116,7 @@ public abstract class PIDCommand extends Command implements Sendable { /** * Adds the given value to the setpoint. - * If {@link PIDCommand#setRange(double, double) setRange(...)} was used, + * If {@link PIDCommand#setInputRange(double, double) setInputRange(...)} was used, * then the bounds will still be honored by this method. * @param deltaSetpoint the change in the setpoint */ @@ -129,7 +125,7 @@ public abstract class PIDCommand extends Command implements Sendable { } /** - * Sets the setpoint to the given value. If {@link PIDCommand#setRange(double, double) setRange(...)} + * Sets the setpoint to the given value. If {@link PIDCommand#setInputRange(double, double) setInputRange(...)} * was called, * then the given setpoint * will be trimmed to fit within the range. @@ -154,6 +150,16 @@ public abstract class PIDCommand extends Command implements Sendable { protected double getPosition() { return returnPIDInput(); } + + /** + * Sets the maximum and minimum values expected from the input and setpoint. + * + * @param minimumInput the minimum value expected from the input and setpoint + * @param maximumInput the maximum value expected from the input and setpoint + */ + protected void setInputRange(double minimumInput, double maximumInput) { + controller.setInputRange(minimumInput, maximumInput); + } /** * Returns the input for the pid loop. diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java index c8baf8bcf9..a55bd76193 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java @@ -126,10 +126,6 @@ public abstract class PIDSubsystem extends Subsystem implements Sendable { * Returns the {@link PIDController} used by this {@link PIDSubsystem}. * Use this if you would like to fine tune the pid loop. * - *

Notice that calling {@link PIDController#setSetpoint(double) setSetpoint(...)} on the controller - * will not result in the setpoint being trimmed to be in - * the range defined by {@link PIDSubsystem#setSetpointRange(double, double) setSetpointRange(...)}.

- * * @return the {@link PIDController} used by this {@link PIDSubsystem} */ public PIDController getPIDController() { @@ -139,7 +135,7 @@ public abstract class PIDSubsystem extends Subsystem implements Sendable { /** * Adds the given value to the setpoint. - * If {@link PIDCommand#setRange(double, double) setRange(...)} was used, + * If {@link PIDSubsystem#setInputRange(double, double) setInputRange(...)} was used, * then the bounds will still be honored by this method. * @param deltaSetpoint the change in the setpoint */ @@ -148,7 +144,7 @@ public abstract class PIDSubsystem extends Subsystem implements Sendable { } /** - * Sets the setpoint to the given value. If {@link PIDCommand#setRange(double, double) setRange(...)} + * Sets the setpoint to the given value. If {@link PIDSubsystem#setInputRange(double, double) setInputRange(...)} * was called, * then the given setpoint * will be trimmed to fit within the range. @@ -197,8 +193,7 @@ public abstract class PIDSubsystem extends Subsystem implements Sendable { /** * Set the absolute error which is considered tolerable for use with * OnTarget. The value is in the same range as the PIDInput values. - * @param t A PIDController.Tolerance object instance that is for example - * AbsoluteTolerance or PercentageTolerance. E.g. setTolerance(new PIDController.AbsoluteTolerance(0.1)) + * @param t the absolute tolerance */ public void setAbsoluteTolerance(double t) { controller.setAbsoluteTolerance(t); @@ -207,8 +202,7 @@ public abstract class PIDSubsystem extends Subsystem implements Sendable { /** * Set the percentage error which is considered tolerable for use with * OnTarget. (Value of 15.0 == 15 percent) - * @param t A PIDController.Tolerance object instance that is for example - * AbsoluteTolerance or PercentageTolerance. E.g. setTolerance(new PIDController.AbsoluteTolerance(0.1)) + * @param p the percent tolerance */ public void setPercentTolerance(double p) { controller.setPercentTolerance(p); diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java index a65f0cbe9a..c658a20a09 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java @@ -57,7 +57,7 @@ public class SmartDashboard { //TODO should we reimplement NamedSendable? /** - * Maps the specified key (where the key is the name of the {@link SmartDashboardNamedData} + * Maps the specified key (where the key is the name of the {@link NamedSendable} SmartDashboardNamedData * to the specified value in this table. * The value can be retrieved by calling the get method with a key that is equal to the original key. * @param value the value @@ -72,7 +72,6 @@ public class SmartDashboard { * @param key the key * @return the value * @throws NetworkTableKeyNotDefined if there is no value mapped to by the key - * @throws IllegalArgumentException if the value mapped to by the key is not a {@link SmartDashboardData} * @throws IllegalArgumentException if the key is null */ public static Sendable getData(String key) { diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/util/BaseSystemNotInitializedException.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/util/BaseSystemNotInitializedException.java index a84761e071..f5877cff8d 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/util/BaseSystemNotInitializedException.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/util/BaseSystemNotInitializedException.java @@ -16,7 +16,7 @@ package edu.wpi.first.wpilibj.util; public class BaseSystemNotInitializedException extends RuntimeException { /** * Create a new BaseSystemNotInitializedException - * @param msg the message to attach to the exception + * @param message the message to attach to the exception */ public BaseSystemNotInitializedException(String message) { super(message); diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/util/BoundaryException.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/util/BoundaryException.java index 676687eb58..d3b70d4902 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/util/BoundaryException.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/util/BoundaryException.java @@ -53,7 +53,7 @@ public class BoundaryException extends RuntimeException { * The lower limit * @param upper * The upper limit - * @return + * @return the message for a boundary exception */ public static String getMessage(double value, double lower, double upper) { return "Value must be between " + lower + " and " + upper + ", " diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java index a7c8d0c8f8..91fce9af9e 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java @@ -91,19 +91,19 @@ public class ADXL345_I2C extends SensorBase implements Accelerometer { m_i2c.write(kDataFormatRegister, kDataFormat_FullRes | value); } - /** {@inheritdoc} */ + /** {@inheritDoc} */ @Override public double getX() { return getAcceleration(Axes.kX); } - /** {@inheritdoc} */ + /** {@inheritDoc} */ @Override public double getY() { return getAcceleration(Axes.kY); } - /** {@inheritdoc} */ + /** {@inheritDoc} */ @Override public double getZ() { return getAcceleration(Axes.kZ); diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java index 80f9dda3f2..6faf159eea 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java @@ -64,12 +64,9 @@ public class ADXL345_SPI extends SensorBase implements Accelerometer { private SPI m_spi; /** - * Constructor. Use this when the device is the first/only device on the bus + * Constructor. * - * @param clk The clock channel - * @param mosi The mosi (output) channel - * @param miso The miso (input) channel - * @param cs The chip select channel + * @param port the Port that the accelerometer is connected to * @param range The range (+ or -) that the accelerometer will measure. */ public ADXL345_SPI(SPI.Port port, Range range) { @@ -132,19 +129,19 @@ public class ADXL345_SPI extends SensorBase implements Accelerometer { m_spi.write(commands, commands.length); } - /** {@inheritdoc} */ + /** {@inheritDoc} */ @Override public double getX() { return getAcceleration(Axes.kX); } - /** {@inheritdoc} */ + /** {@inheritDoc} */ @Override public double getY() { return getAcceleration(Axes.kY); } - /** {@inheritdoc} */ + /** {@inheritDoc} */ @Override public double getZ() { return getAcceleration(Axes.kZ); diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CANJaguar.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CANJaguar.java index 2c45b780d2..c8e0c38045 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CANJaguar.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CANJaguar.java @@ -1157,7 +1157,7 @@ public class CANJaguar implements MotorSafety, PIDOutput, SpeedController, LiveW * position sensing from a quadrature encoder.
* After calling this you must call {@link CANJaguar#enableControl()} or {@link CANJaguar#enableControl(double)} to enable the device. * - * @param endoer The constant {@link CANJaguar#kQuadEncoder} + * @param tag The constant {@link CANJaguar#kQuadEncoder} * @param p The proportional gain of the Jaguar's PID controller. * @param i The integral gain of the Jaguar's PID controller. * @param d The differential gain of the Jaguar's PID controller. @@ -1800,7 +1800,7 @@ public class CANJaguar implements MotorSafety, PIDOutput, SpeedController, LiveW * is added internally) * @param data The up to 8 bytes of data to be sent with the message * @param dataSize Specify how much of the data in "data" to send - * @param periodic If positive, tell Network Communications to send the + * @param period If positive, tell Network Communications to send the * message every "period" milliseconds. */ protected void sendMessage(int messageID, byte[] data, int dataSize, int period) { @@ -1808,7 +1808,7 @@ public class CANJaguar implements MotorSafety, PIDOutput, SpeedController, LiveW } /** - * Send a message to the Jaguar, non-periodly + * Send a message to the Jaguar, non-periodically * * @param messageID The messageID to be used on the CAN bus (device number * is added internally) @@ -1823,7 +1823,7 @@ public class CANJaguar implements MotorSafety, PIDOutput, SpeedController, LiveW * Request a message from the Jaguar, but don't wait for it to arrive. * * @param messageID The message to request - * @param periodic If positive, tell Network Communications to request the + * @param period If positive, tell Network Communications to request the * message every "period" milliseconds. */ protected void requestMessage(int messageID, int period) { @@ -1847,7 +1847,7 @@ public class CANJaguar implements MotorSafety, PIDOutput, SpeedController, LiveW * @param messageID The messageID to read from the CAN bus (device number is added internally) * @param data The up to 8 bytes of data that was received with the message * - * @throw CANMessageNotFoundException if there's not new message available + * @throws CANMessageNotFoundException if there's not new message available */ protected void getMessage(int messageID, int messageMask, byte[] data) throws CANMessageNotFoundException { messageID |= m_deviceNumber; diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Compressor.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Compressor.java index 306afbfa93..a240ec9c27 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Compressor.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Compressor.java @@ -26,7 +26,7 @@ public class Compressor extends SensorBase implements LiveWindowSendable { /** * Create an instance of the Compressor - * @param pcmID + * @param pcmId * The PCM CAN device ID. Most robots that use PCM will have a single module. Use this * for supporting a second module other than the default. */ @@ -71,7 +71,7 @@ public class Compressor extends SensorBase implements LiveWindowSendable { /** * Get the enabled status of the compressor - * @returns true if the compressor is on + * @return true if the compressor is on */ public boolean enabled() { ByteBuffer status = ByteBuffer.allocateDirect(4); diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Counter.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Counter.java index 07d676a9a8..aa4c2fc0a2 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Counter.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Counter.java @@ -466,7 +466,7 @@ public class Counter extends SensorBase implements CounterBase, * Read the current scaled counter value. Read the value at this instant, * scaled by the distance per pulse (defaults to 1). * - * @return + * @return The distance since the last reset */ public double getDistance() { return get() * m_distancePerPulse; @@ -581,7 +581,7 @@ public class Counter extends SensorBase implements CounterBase, * most recent count. This can be used for velocity calculations to * determine shaft speed. * - * @returns The period of the last two pulses in units of seconds. + * @return The period of the last two pulses in units of seconds. */ @Override public double getPeriod() { diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java index 6d5e2c8c4b..7ca88e7045 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java @@ -58,17 +58,17 @@ public abstract class InterruptableSensorBase extends SensorBase { } /** - * @return + * @return true if this is an analog trigger */ abstract boolean getAnalogTriggerForRouting(); /** - * @return + * @return channel routing number */ abstract int getChannelForRouting(); /** - * @return + * @return module routing number */ abstract byte getModuleForRouting(); @@ -76,7 +76,7 @@ public abstract class InterruptableSensorBase extends SensorBase { * Request interrupts asynchronously on this digital input. * * @param handler - * The {@link #InterruptHandlerFunction} that contains the method + * The {@link InterruptHandlerFunction} that contains the method * {@link InterruptHandlerFunction#interruptFired(int, Object)} that * will be called whenever there is an interrupt on this device. * Request interrupts in synchronus mode where the user program diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SPI.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SPI.java index 46d5e6796b..51116d981c 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SPI.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SPI.java @@ -46,7 +46,7 @@ public class SPI extends SensorBase { /** * Constructor * - * @param SPIport the physical SPI port + * @param port the physical SPI port */ public SPI(Port port) { ByteBuffer status = ByteBuffer.allocateDirect(4); diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Servo.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Servo.java index 49c3fd8e29..3d5b402877 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Servo.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/Servo.java @@ -24,8 +24,8 @@ public class Servo extends PWM { private static final double kMaxServoAngle = 180.0; private static final double kMinServoAngle = 0.0; - private static final double kDefaultMaxServoPWM = 2.4; - private static final double kDefaultMinServoPWM = .6; + protected static final double kDefaultMaxServoPWM = 2.4; + protected static final double kDefaultMinServoPWM = .6; /** * Common initialization code called by all constructors.