Update Javadocs for Java (fixes artf3761 and artf3953)

Change-Id: I0b5e752e8f6377770163dcdc61aa79ad4c7cbe94
This commit is contained in:
Kevin O'Connor
2014-12-29 15:38:08 -05:00
parent eddb0b20b0
commit b4c5a3af77
31 changed files with 167 additions and 125 deletions

View File

@@ -53,7 +53,7 @@ public class ADXL345_I2C extends SensorBase implements Accelerometer {
/**
* Constructor.
*
* @param port The I2C port the accelerometer is attached to
* @param range The range (+ or -) that the accelerometer will measure.
*/
public ADXL345_I2C(I2C.Port port, Range range) {
@@ -132,7 +132,7 @@ public class ADXL345_I2C extends SensorBase implements Accelerometer {
/**
* Get the acceleration of all axes in Gs.
*
* @return Acceleration measured on all axes of the ADXL345 in Gs.
* @return An object containing the acceleration measured on each axis of the ADXL345 in Gs.
*/
public AllAxes getAccelerations() {
AllAxes data = new AllAxes();

View File

@@ -69,7 +69,7 @@ public class ADXL345_SPI extends SensorBase implements Accelerometer {
/**
* Constructor.
*
* @param port the Port that the accelerometer is connected to
* @param port The SPI 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) {
@@ -170,7 +170,7 @@ public class ADXL345_SPI extends SensorBase implements Accelerometer {
/**
* Get the acceleration of all axes in Gs.
*
* @return Acceleration measured on all axes of the ADXL345 in Gs.
* @return An object containing the acceleration measured on each axis of the ADXL345 in Gs.
*/
public ADXL345_SPI.AllAxes getAccelerations() {
ADXL345_SPI.AllAxes data = new ADXL345_SPI.AllAxes();

View File

@@ -39,7 +39,7 @@ public class AnalogAccelerometer extends SensorBase implements PIDSource, LiveWi
* Create a new instance of an accelerometer.
*
* The constructor allocates desired analog channel.
* @param channel the port that the accelerometer is on
* @param channel The channel number for the analog input the accelerometer is connected to
*/
public AnalogAccelerometer(final int channel) {
m_allocatedChannel = true;
@@ -52,7 +52,7 @@ public class AnalogAccelerometer extends SensorBase implements PIDSource, LiveWi
* Make a new instance of accelerometer given an AnalogChannel. This is particularly
* useful if the port is going to be read as an analog channel as well as through
* the Accelerometer class.
* @param channel an already initialized analog channel
* @param channel The existing AnalogInput object for the analog input the accelerometer is connected to
*/
public AnalogAccelerometer(AnalogInput channel) {
m_allocatedChannel = false;
@@ -87,7 +87,7 @@ public class AnalogAccelerometer extends SensorBase implements PIDSource, LiveWi
* Set the accelerometer sensitivity.
*
* This sets the sensitivity of the accelerometer used for calculating the acceleration.
* The sensitivity varys by accelerometer model. There are constants defined for various models.
* The sensitivity varies by accelerometer model. There are constants defined for various models.
*
* @param sensitivity The sensitivity of accelerometer in Volts per G.
*/
@@ -98,7 +98,7 @@ public class AnalogAccelerometer extends SensorBase implements PIDSource, LiveWi
/**
* Set the voltage that corresponds to 0 G.
*
* The zero G voltage varys by accelerometer model. There are constants defined for various models.
* The zero G voltage varies by accelerometer model. There are constants defined for various models.
*
* @param zero The zero G voltage.
*/

View File

@@ -52,8 +52,7 @@ public class AnalogInput extends SensorBase implements PIDSource,
/**
* Construct an analog channel.
*
* @param channel
* The channel number to represent.
* @param channel The channel number to represent. 0-3 are on-board 4-7 are on the MXP port.
*/
public AnalogInput(final int channel) {
m_channel = channel;
@@ -108,10 +107,10 @@ public class AnalogInput extends SensorBase implements PIDSource,
/**
* Get a sample from the output of the oversample and average engine for
* this channel. The sample is 12-bit + the value configured in
* this channel. The sample is 12-bit + the bits configured in
* SetOversampleBits(). The value configured in setAverageBits() will cause
* this value to be averaged 2**bits number of samples. This is not a
* sliding window. The sample will not change until 2**(OversamplBits +
* this value to be averaged 2^bits number of samples. This is not a
* sliding window. The sample will not change until 2^(OversampleBits +
* AverageBits) samples have been acquired from this channel. Use
* getAverageVoltage() to get the analog value in calibrated units.
*
@@ -208,7 +207,7 @@ public class AnalogInput extends SensorBase implements PIDSource,
/**
* Set the number of averaging bits. This sets the number of averaging bits.
* The actual number of averaged samples is 2**bits. The averaging is done
* The actual number of averaged samples is 2^bits. The averaging is done
* automatically in the FPGA.
*
* @param bits
@@ -224,7 +223,7 @@ public class AnalogInput extends SensorBase implements PIDSource,
/**
* Get the number of averaging bits. This gets the number of averaging bits
* from the FPGA. The actual number of averaged samples is 2**bits. The
* from the FPGA. The actual number of averaged samples is 2^bits. The
* averaging is done automatically in the FPGA.
*
* @return The number of averaging bits.
@@ -240,7 +239,7 @@ public class AnalogInput extends SensorBase implements PIDSource,
/**
* Set the number of oversample bits. This sets the number of oversample
* bits. The actual number of oversampled values is 2**bits. The
* bits. The actual number of oversampled values is 2^bits. The
* oversampling is done automatically in the FPGA.
*
* @param bits
@@ -256,7 +255,7 @@ public class AnalogInput extends SensorBase implements PIDSource,
/**
* Get the number of oversample bits. This gets the number of oversample
* bits from the FPGA. The actual number of oversampled values is 2**bits.
* bits from the FPGA. The actual number of oversampled values is 2^bits.
* The oversampling is done automatically in the FPGA.
*
* @return The number of oversample bits.
@@ -290,7 +289,7 @@ public class AnalogInput extends SensorBase implements PIDSource,
}
/**
* Set an inital value for the accumulator.
* Set an initial value for the accumulator.
*
* This will be added to all values returned to the user.
*
@@ -325,11 +324,11 @@ public class AnalogInput extends SensorBase implements PIDSource,
*
* The center value is subtracted from each A/D value before it is added to
* the accumulator. This is used for the center value of devices like gyros
* and accelerometers to make integration work and to take the device offset
* and accelerometers to take the device offset
* into account when integrating.
*
* This center value is based on the output of the oversampled and averaged
* source from channel 1. Because of this, any non-zero oversample bits will
* source the accumulator channel. Because of this, any non-zero oversample bits will
* affect the size of the value for this field.
*/
public void setAccumulatorCenter(int center) {
@@ -342,6 +341,7 @@ public class AnalogInput extends SensorBase implements PIDSource,
/**
* Set the accumulator's deadband.
* @param deadband The deadband size in ADC codes (12-bit value)
*/
public void setAccumulatorDeadband(int deadband) {
ByteBuffer status = ByteBuffer.allocateDirect(4);
@@ -354,7 +354,7 @@ public class AnalogInput extends SensorBase implements PIDSource,
/**
* Read the accumulated value.
*
* Read the value that has been accumulating on channel 1. The accumulator
* Read the value that has been accumulating. The accumulator
* is attached after the oversample and average engine.
*
* @return The 64-bit value accumulated since the last Reset().
@@ -433,10 +433,11 @@ public class AnalogInput extends SensorBase implements PIDSource,
}
/**
* Set the sample rate.
* Set the sample rate per channel.
*
* This is a global setting for all channels.
*
* The maximum rate is 500kS/s divided by the number of channels in use.
* This is 62500 samples/s per channel if all 8 channels are used.
* @param samplesPerSecond The number of samples per second.
*/
public static void setGlobalSampleRate(final double samplesPerSecond) {

View File

@@ -70,7 +70,7 @@ public class AnalogTrigger {
* Constructor for an analog trigger given a channel number.
*
* @param channel
* the port to use for the analog trigger
* the port to use for the analog trigger 0-3 are on-board, 4-7 are on the MXP port
*/
public AnalogTrigger(final int channel) {
initTrigger(channel);

View File

@@ -36,8 +36,8 @@ public class Compressor extends SensorBase implements LiveWindowSendable {
/**
* Create an instance of the Compressor
* Makes a new instance of the compressor using the default address. Additional modules can be
* supported by making a new instancce and specifying the CAN ID
* Makes a new instance of the compressor using the default PCM ID (0). Additional modules can be
* supported by making a new instance and specifying the CAN ID
*/
public Compressor() {
initCompressor(getDefaultSolenoidModule());

View File

@@ -18,7 +18,7 @@ public class ControllerPower
{
/**
* Get the input voltage to the robot controller
* @return The controller input voltage value
* @return The controller input voltage value in Volts
*/
public static double getInputVoltage()
{
@@ -31,7 +31,7 @@ public class ControllerPower
/**
* Get the input current to the robot controller
* @return The controller input current value
* @return The controller input current value in Amps
*/
public static double getInputCurrent()
{
@@ -44,7 +44,7 @@ public class ControllerPower
/**
* Get the voltage of the 3.3V rail
* @return The controller 3.3V rail voltage value
* @return The controller 3.3V rail voltage value in Volts
*/
public static double getVoltage3V3()
{
@@ -57,7 +57,7 @@ public class ControllerPower
/**
* Get the current output of the 3.3V rail
* @return The controller 3.3V rail output current value
* @return The controller 3.3V rail output current value in Volts
*/
public static double getCurrent3V3()
{
@@ -97,7 +97,7 @@ public class ControllerPower
/**
* Get the voltage of the 5V rail
* @return The controller 5V rail voltage value
* @return The controller 5V rail voltage value in Volts
*/
public static double getVoltage5V()
{
@@ -110,7 +110,7 @@ public class ControllerPower
/**
* Get the current output of the 5V rail
* @return The controller 5V rail output current value
* @return The controller 5V rail output current value in Amps
*/
public static double getCurrent5V()
{
@@ -150,7 +150,7 @@ public class ControllerPower
/**
* Get the voltage of the 6V rail
* @return The controller 6V rail voltage value
* @return The controller 6V rail voltage value in Volts
*/
public static double getVoltage6V()
{
@@ -163,7 +163,7 @@ public class ControllerPower
/**
* Get the current output of the 6V rail
* @return The controller 6V rail output current value
* @return The controller 6V rail output current value in Amps
*/
public static double getCurrent6V()
{

View File

@@ -106,7 +106,7 @@ public class Counter extends SensorBase implements CounterBase,
/**
* Create an instance of a counter from a Digital Input. This is used if an
* existing digital input is to be shared by multiple other objects such as
* encoders.
* encoders or if the Digital Source is not a DIO channel (such as an Analog Trigger)
*
* The counter will start counting immediately.
*
@@ -127,7 +127,7 @@ public class Counter extends SensorBase implements CounterBase,
* The counter will start counting immediately.
*
* @param channel
* the digital input channel to count
* the DIO channel to use as the up source. 0-9 are on-board, 10-25 are on the MXP
*/
public Counter(int channel) {
initCounter(Mode.kTwoPulse);
@@ -220,7 +220,7 @@ public class Counter extends SensorBase implements CounterBase,
* Set the upsource for the counter as a digital input channel.
*
* @param channel
* the digital port to count
* the DIO channel to count 0-9 are on-board, 10-25 are on the MXP
*/
public void setUpSource(int channel) {
setUpSource(new DigitalInput(channel));
@@ -308,7 +308,7 @@ public class Counter extends SensorBase implements CounterBase,
* Set the down counting source to be a digital input channel.
*
* @param channel
* the digital port to count
* the DIO channel to count 0-9 are on-board, 10-25 are on the MXP
*/
public void setDownSource(int channel) {
setDownSource(new DigitalInput(channel));

View File

@@ -32,7 +32,7 @@ public class DigitalInput extends DigitalSource implements LiveWindowSendable {
* given a channel.
*
* @param channel
* the port for the digital input
* the DIO channel for the digital input 0-9 are on-board, 10-25 are on the MXP
*/
public DigitalInput(int channel) {
initDigitalPort(channel, true);
@@ -45,7 +45,7 @@ public class DigitalInput extends DigitalSource implements LiveWindowSendable {
* Get the value from a digital input channel. Retrieve the value of a
* single digital input channel from the FPGA.
*
* @return the stats of the digital input
* @return the status of the digital input
*/
public boolean get() {
ByteBuffer status = ByteBuffer.allocateDirect(4);

View File

@@ -34,7 +34,7 @@ public class DigitalOutput extends DigitalSource implements LiveWindowSendable {
* output given a channel.
*
* @param channel
* the port to use for the digital output
* the DIO channel to use for the digital output. 0-9 are on-board, 10-25 are on the MXP
*/
public DigitalOutput(int channel) {
initDigitalPort(channel, false);

View File

@@ -75,9 +75,9 @@ public class DoubleSolenoid extends SolenoidBase implements LiveWindowSendable {
/**
* Constructor.
*
* @param forwardChannel The forward channel on the module to control.
* @param reverseChannel The reverse channel on the module to control.
* Uses the default PCM ID of 0
* @param forwardChannel The forward channel number on the PCM.
* @param reverseChannel The reverse channel number on the PCM.
*/
public DoubleSolenoid(final int forwardChannel, final int reverseChannel) {
super(getDefaultSolenoidModule());
@@ -111,7 +111,7 @@ public class DoubleSolenoid extends SolenoidBase implements LiveWindowSendable {
/**
* Set the value of a solenoid.
*
* @param value Move the solenoid to forward, reverse, or don't move it.
* @param value The value to set (Off, Forward, Reverse)
*/
public void set(final Value value) {
byte rawValue = 0;
@@ -147,7 +147,7 @@ public class DoubleSolenoid extends SolenoidBase implements LiveWindowSendable {
* Check if the forward solenoid is blacklisted.
* If a solenoid is shorted, it is added to the blacklist and
* disabled until power cycle, or until faults are cleared.
* @see clearAllPCMStickyFaults()
* @see #clearAllPCMStickyFaults()
*
* @return If solenoid is disabled due to short.
*/
@@ -159,7 +159,7 @@ public class DoubleSolenoid extends SolenoidBase implements LiveWindowSendable {
* Check if the reverse solenoid is blacklisted.
* If a solenoid is shorted, it is added to the blacklist and
* disabled until power cycle, or until faults are cleared.
* @see clearAllPCMStickyFaults()
* @see #clearAllPCMStickyFaults()
*
* @return If solenoid is disabled due to short.
*/

View File

@@ -183,7 +183,7 @@ public class DriverStation implements RobotState.Interface {
/**
* Read the battery voltage.
*
* @return The battery voltage.
* @return The battery voltage in Volts.
*/
public double getBatteryVoltage() {
IntBuffer status = ByteBuffer.allocateDirect(4).asIntBuffer();
@@ -193,6 +193,11 @@ public class DriverStation implements RobotState.Interface {
return voltage;
}
/**
* Reports errors telated to unplugged joysticks
* Throttles the errors so that they don't overwhelm the DS
*/
private void reportJoystickUnpluggedError(String message) {
double currentTime = Timer.getFPGATimestamp();
if (currentTime > m_nextMessageTime) {
@@ -233,9 +238,10 @@ public class DriverStation implements RobotState.Interface {
}
/**
* Returns the number of axis on a given joystick port
* Returns the number of axes on a given joystick port
*
* @param stick The joystick port number
* @return The number of axes on the indicated joystick
*/
public synchronized int getStickAxisCount(int stick){
@@ -272,6 +278,7 @@ public class DriverStation implements RobotState.Interface {
* Returns the number of POVs on a given joystick port
*
* @param stick The joystick port number
* @return The number of POVs on the indicated joystick
*/
public synchronized int getStickPOVCount(int stick){
@@ -284,7 +291,6 @@ public class DriverStation implements RobotState.Interface {
/**
* The state of the buttons on the joystick.
* 12 buttons (4 msb are unused) from the joystick.
*
* @param stick The joystick to read.
* @return The state of the buttons on the joystick.
@@ -323,14 +329,15 @@ public class DriverStation implements RobotState.Interface {
}
/**
* Gets the number of buttons on a joystick
* Gets the number of buttons on a joystick
*
* @param stick the joystick port number
* @param stick The joystick port number
* @return The number of buttons on the indicated joystick
*/
public synchronized int getStickButtonCount(int stick){
if(stick < 0 || stick >= kJoystickPorts) {
throw new RuntimeException("Joystick index is out of range, should be 0-3");
throw new RuntimeException("Joystick index is out of range, should be 0-5");
}
@@ -389,6 +396,12 @@ public class DriverStation implements RobotState.Interface {
return !(isAutonomous() || isTest());
}
/**
* Gets a value indicating whether the FPGA outputs are enabled. The outputs may be disabled
* if the robot is disabled or e-stopped, the watdhog has expired, or if the roboRIO browns out.
*
* @return True if the FPGA outputs are enabled.
*/
public boolean isSysActive() {
ByteBuffer status = ByteBuffer.allocateDirect(4);
status.order(ByteOrder.LITTLE_ENDIAN);
@@ -397,6 +410,11 @@ public class DriverStation implements RobotState.Interface {
return retVal;
}
/**
* Check if the system is browned out.
*
* @return True if the system is browned out
*/
public boolean isBrownedOut() {
ByteBuffer status = ByteBuffer.allocateDirect(4);
status.order(ByteOrder.LITTLE_ENDIAN);
@@ -484,16 +502,15 @@ public class DriverStation implements RobotState.Interface {
return controlWord.getDSAttached();
}
/**
* Return the approximate match time
* The FMS does not currently send the official match time to the robots
* This returns the time since the enable signal sent from the Driver Station
* At the beginning of autonomous, the time is reset to 0.0 seconds
* At the beginning of teleop, the time is reset to +15.0 seconds
* If the robot is disabled, this returns 0.0 seconds
* Warning: This is not an official time (so it cannot be used to argue with referees)
* @return Match time in seconds since the beginning of autonomous
*/
/**
* Return the approximate match time
* The FMS does not send an official match time to the robots, but does send an approximate match time.
* The value will count down the time remaining in the current period (auto or teleop).
* Warning: This is not an official time (so it cannot be used to dispute ref calls or guarantee that a function
* will trigger before the match ends)
* The Practice Match function of the DS approximates the behaviour seen on the field.
* @return Time remaining in current match period (auto or teleop) in seconds
*/
public double getMatchTime() {
return FRCNetworkCommunicationsLibrary.HALGetMatchTime();
}

View File

@@ -116,9 +116,9 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, LiveW
* The encoder will start counting immediately.
*
* @param aChannel
* The a channel digital input channel.
* The a channel DIO channel. 0-9 are on-board, 10-25 are on the MXP port
* @param bChannel
* The b channel digital input channel.
* The b channel DIO channel. 0-9 are on-board, 10-25 are on the MXP port
* @param reverseDirection
* represents the orientation of the encoder and inverts the
* output values if necessary so forward represents positive

View File

@@ -44,8 +44,8 @@ public class GearTooth extends Counter {
/**
* Construct a GearTooth sensor given a channel.
*
* @param channel The GPIO channel that the sensor is connected to.
* @param directionSensitive Enable the pulse length decoding in hardware to specify count direction.
* @param channel The DIO channel that the sensor is connected to. 0-9 are on-board, 10-25 are on the MXP port
* @param directionSensitive True to enable the pulse length decoding in hardware to specify count direction.
*/
public GearTooth(final int channel, boolean directionSensitive) {
super(channel);
@@ -60,10 +60,10 @@ public class GearTooth extends Counter {
/**
* Construct a GearTooth sensor given a digital input.
* This should be used when sharing digial inputs.
* This should be used when sharing digital inputs.
*
* @param source An object that fully descibes the input that the sensor is connected to.
* @param directionSensitive Enable the pulse length decoding in hardware to specify count direction.
* @param source An existing DigitalSource object (such as a DigitalInput)
* @param directionSensitive True to enable the pulse length decoding in hardware to specify count direction.
*/
public GearTooth(DigitalSource source, boolean directionSensitive) {
super(source);

View File

@@ -39,7 +39,7 @@ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable {
/**
* Initialize the gyro. Calibrate the gyro by running for a number of
* samples and computing the center value for this part. Then use the center
* samples and computing the center value. Then use the center
* value as the Accumulator center value for subsequent measurements. It's
* important to make sure that the robot is not moving while the centering
* calculations are in progress, this is typically done when the robot is
@@ -82,10 +82,10 @@ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable {
}
/**
* Gyro constructor with only a channel.
* Gyro constructor using the channel number
*
* @param channel
* The analog channel the gyro is connected to.
* The analog channel the gyro is connected to. 0-3 are on-board 4-7 are on the MXP port.
*/
public Gyro(int channel) {
this(new AnalogInput(channel));
@@ -97,7 +97,7 @@ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable {
* constructor when the analog channel needs to be shared.
*
* @param channel
* The AnalogChannel object that the gyro is connected to.
* The AnalogInput object that the gyro is connected to.
*/
public Gyro(AnalogInput channel) {
m_analog = channel;
@@ -135,9 +135,9 @@ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable {
*
* The angle is based on the current accumulator value corrected by the
* oversampling rate, the gyro type and the A/D calibration values. The
* angle is continuous, that is can go beyond 360 degrees. This make
* angle is continuous, that is it will continue from 360 to 361 degrees. This allows
* algorithms that wouldn't want to see a discontinuity in the gyro output
* as it sweeps past 0 on the second time around.
* as it sweeps past from 360 to 0 on the second time around.
*
* @return the current heading of the robot in degrees. This heading is
* based on integration of the returned rate from the gyro.
@@ -179,13 +179,13 @@ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable {
}
/**
* Set the gyro type based on the sensitivity. This takes the number of
* Set the gyro sensitivity. This takes the number of
* volts/degree/second sensitivity of the gyro and uses it in subsequent
* calculations to allow the code to work with multiple gyros.
* calculations to allow the code to work with multiple gyros. This value
* is typically found in the gyro datasheet.
*
* @param voltsPerDegreePerSecond
* The type of gyro specified as the voltage that represents one
* degree/second.
* The sensitivity in Volts/degree/second.
*/
public void setSensitivity(double voltsPerDegreePerSecond) {
m_voltsPerDegreePerSecond = voltsPerDegreePerSecond;
@@ -205,7 +205,7 @@ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable {
}
/**
* Set which parameter of the encoder you are using as a process control
* Set which parameter of the gyro you are using as a process control
* variable. The Gyro class supports the rate and angle parameters
*
* @param pidSource
@@ -217,9 +217,10 @@ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable {
}
/**
* Get the angle of the gyro for use with PIDControllers
* Get the output of the gyro for use with PIDControllers.
* May be the angle or rate depending on the set PIDSourceParameter
*
* @return the current angle according to the gyro
* @return the output according to the gyro
*/
@Override
public double pidGet() {

View File

@@ -44,6 +44,7 @@ public class I2C extends SensorBase {
/**
* Constructor.
*
* @param port The I2C port the device is connected to.
* @param deviceAddress
* The address of the device on the I2C bus.
*/

View File

@@ -42,7 +42,7 @@ public class Jaguar extends SafePWM implements SpeedController {
/**
* Constructor.
*
* @param channel The PWM channel that the Jaguar is attached to.
* @param channel The PWM channel that the Jaguar is attached to. 0-9 are on-board, 10-19 are on the MXP port
*/
public Jaguar(final int channel) {
super(channel);

View File

@@ -305,12 +305,11 @@ public class Joystick extends GenericHID {
}
/**
* Get the button value for buttons 1 through 12.
* Get the button value (starting at button 1)
*
* The buttons are returned in a single 16 bit value with one bit representing the state
* of each button. The appropriate button is returned as a boolean value.
* The appropriate button is returned as a boolean value.
*
* @param button The button number to be read.
* @param button The button number to be read (starting at 1).
* @return The state of the button.
*/
public boolean getRawButton(final int button) {
@@ -327,6 +326,7 @@ public class Joystick extends GenericHID {
/**
* Get the state of a POV on the joystick.
*
* @param pov The index of the POV to read (starting at 0)
* @return the angle of the POV in degrees, or -1 if the POV is not pressed.
*/
public int getPOV(int pov) {

View File

@@ -23,18 +23,19 @@ import edu.wpi.first.wpilibj.hal.HALUtil;
/**
* Class implements the PWM generation in the FPGA.
* Values supplied as arguments for PWM outputs range from -1.0 to 1.0. They are mapped
* to the hardware dependent values, in this case 0-255 for the FPGA.
*
* The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They are mapped
* to the hardware dependent values, in this case 0-2000 for the FPGA.
* Changes are immediately sent to the FPGA, and the update occurs at the next
* FPGA cycle. There is no delay.
*
* As of revision 0.1.4 of the FPGA, the FPGA interprets the 0-255 values as follows:
* 255 = full "forward"
* 254 to 129 = linear scaling from "full forward" to "center"
* 128 = center value
* 127 to 2 = linear scaling from "center" to "full reverse"
* 1 = full "reverse"
* 0 = disabled (i.e. PWM output is held low)
* As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-255 values as follows:
* - 2000 = maximum pulse width
* - 1999 to 1001 = linear scaling from "full forward" to "center"
* - 1000 = center value
* - 999 to 2 = linear scaling from "center" to "full reverse"
* - 1 = minimum pulse width (currently .5ms)
* - 0 = disabled (i.e. PWM output is held low)
*/
public class PWM extends SensorBase implements LiveWindowSendable {
/**
@@ -108,6 +109,7 @@ public class PWM extends SensorBase implements LiveWindowSendable {
* for creating PWM instances. Checks channel value ranges and allocates
* the appropriate channel. The allocation is only done to help users
* ensure that they don't double assign channels.
* @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port
*/
private void initPWM(final int channel) {
checkPWMChannel(channel);

View File

@@ -23,6 +23,7 @@ public class PowerDistributionPanel extends SensorBase {
}
/**
* Query the input voltage of the PDP
* @return The voltage of the PDP
*/
public double getVoltage() {
@@ -35,6 +36,7 @@ public class PowerDistributionPanel extends SensorBase {
}
/**
* Query the temperature of the PDP
* @return The temperature of the PDP in degrees Celsius
*/
public double getTemperature() {
@@ -47,6 +49,7 @@ public class PowerDistributionPanel extends SensorBase {
}
/**
* Query the current of a single channel of the PDP
* @return The current of one of the PDP channels (channels 0-15) in Amperes
*/
public double getCurrent(int channel) {
@@ -61,7 +64,8 @@ public class PowerDistributionPanel extends SensorBase {
}
/**
* @return The current of all the channels
* Query the current of all monitored PDP channels (0-15)
* @return The current of all the channels
*/
public double getTotalCurrent(){
ByteBuffer status = ByteBuffer.allocateDirect(4);
@@ -73,7 +77,8 @@ public class PowerDistributionPanel extends SensorBase {
}
/**
* @return the total power
* Query the total power drawn from the monitored PDP channels
* @return the total power
*/
public double getTotalPower(){
ByteBuffer status = ByteBuffer.allocateDirect(4);
@@ -85,6 +90,10 @@ public class PowerDistributionPanel extends SensorBase {
}
/**
* Query the total energy drawn from the monitored PDP channels
* @return the total power
*/
public double getTotalEnergy(){
ByteBuffer status = ByteBuffer.allocateDirect(4);
status.order(ByteOrder.LITTLE_ENDIAN);
@@ -94,6 +103,9 @@ public class PowerDistributionPanel extends SensorBase {
return energy;
}
/**
* Reset the total energy to 0
*/
public void resetTotalEnergy(){
ByteBuffer status = ByteBuffer.allocateDirect(4);
status.order(ByteOrder.LITTLE_ENDIAN);
@@ -101,6 +113,9 @@ public class PowerDistributionPanel extends SensorBase {
PDPJNI.resetPDPTotalEnergy(status.asIntBuffer());
}
/**
* Clear all PDP sticky faults
*/
public void clearStickyFaults(){
ByteBuffer status = ByteBuffer.allocateDirect(4);
status.order(ByteOrder.LITTLE_ENDIAN);

View File

@@ -134,6 +134,9 @@ public abstract class RobotBase {
* This hook is called right before startCompetition(). By default, tell the
* DS that the robot is now ready to be enabled. If you don't want for the
* robot to be enabled yet, you can override this method to do nothing.
* If you do so, you will need to call
* FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationOvserveUserProgramStarting() from
* your code when you are ready for the robot to be enabled.
*/
protected void prestart() {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramStarting();

View File

@@ -70,7 +70,8 @@ public class SPI extends SensorBase {
/**
* Configure the rate of the generated clock signal.
* The default and maximum value is 500,000 Hz.
* The default value is 500,000 Hz.
* The maximum value is 4,000,000 Hz.
*
* @param hz The clock rate in Hertz.
*/

View File

@@ -27,7 +27,7 @@ public class SafePWM extends PWM implements MotorSafety {
/**
* Constructor for a SafePWM object taking a channel number
* @param channel The channel number to be used for the underlying PWM object
* @param channel The channel number to be used for the underlying PWM object. 0-9 are on-board, 10-19 are on the MXP port.
*/
public SafePWM(final int channel) {
super(channel);

View File

@@ -184,6 +184,7 @@ public class SerialPort {
* Create an instance of a Serial Port class.
*
* @param baudRate The baud rate to configure the serial port.
* @param port The Serial port to use
* @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
* @param parity Select the type of parity checking to use.
* @param stopBits The number of stop bits to use as defined by the enum StopBits.

View File

@@ -48,7 +48,7 @@ public class Servo extends PWM {
* By default {@value #kDefaultMaxServoPWM} ms is used as the maxPWM value<br>
* By default {@value #kDefaultMinServoPWM} ms is used as the minPWM value<br>
*
* @param channel The PWM channel to which the servo is attached.
* @param channel The PWM channel to which the servo is attached. 0-9 are on-board, 10-19 are on the MXP port
*/
public Servo(final int channel) {
super(channel);

View File

@@ -51,9 +51,9 @@ public class Solenoid extends SolenoidBase implements LiveWindowSendable {
}
/**
* Constructor.
* Constructor using the default PCM ID (0)
*
* @param channel The channel on the module to control.
* @param channel The channel on the PCM to control.
*/
public Solenoid(final int channel) {
super(getDefaultSolenoidModule());
@@ -64,8 +64,8 @@ public class Solenoid extends SolenoidBase implements LiveWindowSendable {
/**
* Constructor.
*
* @param moduleNumber The module number of the solenoid module to use.
* @param channel The channel on the module to control.
* @param moduleNumber The CAN ID of the PCM the solenoid is attached to.
* @param channel The channel on the PCM to control (0..7).
*/
public Solenoid(final int moduleNumber, final int channel) {
super(moduleNumber);

View File

@@ -26,7 +26,7 @@ public abstract class SolenoidBase extends SensorBase {
/**
* Constructor.
*
* @param moduleNumber The number of the solenoid module to use.
* @param moduleNumber The PCM CAN ID
*/
public SolenoidBase(final int moduleNumber) {
m_moduleNumber = moduleNumber;
@@ -74,7 +74,7 @@ public abstract class SolenoidBase extends SensorBase {
*
* If a solenoid is shorted, it is added to the blacklist and
* disabled until power cycle, or until faults are cleared.
* @see clearAllPCMStickyFaults()
* @see #clearAllPCMStickyFaults()
*
* @return The solenoid blacklist of all 8 solenoids on the module.
*/

View File

@@ -41,9 +41,9 @@ public class Talon extends SafePWM implements SpeedController {
}
/**
* Constructor.
* Constructor for a Talon (original or Talon SR)
*
* @param channel The PWM channel that the Talon is attached to.
* @param channel The PWM channel that the Talon is attached to. 0-9 are on-board, 10-19 are on the MXP port
*/
public Talon(final int channel) {
super(channel);

View File

@@ -25,11 +25,11 @@ public class TalonSRX extends SafePWM implements SpeedController {
* the deadband or inability to saturate the controller in either direction, calibration is recommended.
* The calibration procedure can be found in the TalonSRX User Manual available from CTRE.
*
* - 2.037ms = full "forward"
* - 1.539ms = the "high end" of the deadband range
* - 1.513ms = center of the deadband range (off)
* - 1.487ms = the "low end" of the deadband range
* - .989ms = full "reverse"
* - 2.0004ms = full "forward"
* - 1.52ms = the "high end" of the deadband range
* - 1.50ms = center of the deadband range (off)
* - 1.48ms = the "low end" of the deadband range
* - .997ms = full "reverse"
*/
protected void initTalonSRX() {
setBounds(2.004, 1.52, 1.50, 1.48, .997);
@@ -42,9 +42,9 @@ public class TalonSRX extends SafePWM implements SpeedController {
}
/**
* Constructor.
* Constructor for a TalonSRX connected via PWM
*
* @param channel The PWM channel that the Talon is attached to.
* @param channel The PWM channel that the TalonSRX is attached to. 0-9 are on-board, 10-19 are on the MXP port
*/
public TalonSRX(final int channel) {
super(channel);

View File

@@ -24,7 +24,7 @@ public class Victor extends SafePWM implements SpeedController {
*
* Note that the Victor uses the following bounds for PWM values. These values were determined
* empirically and optimized for the Victor 888. These values should work reasonably well for
* Victor 884 controllers also but if users experience issues such as asymmetric behavior around
* Victor 884 controllers also but if users experience issues such as asymmetric behaviour around
* the deadband or inability to saturate the controller in either direction, calibration is recommended.
* The calibration procedure can be found in the Victor 884 User Manual available from VEX Robotics:
* http://content.vexrobotics.com/docs/ifi-v884-users-manual-9-25-06.pdf
@@ -48,7 +48,7 @@ public class Victor extends SafePWM implements SpeedController {
/**
* Constructor.
*
* @param channel The PWM channel that the Victor is attached to.
* @param channel The PWM channel that the Victor is attached to. 0-9 are on-board, 10-19 are on the MXP port
*/
public Victor(final int channel) {
super(channel);

View File

@@ -24,11 +24,11 @@ public class VictorSP extends SafePWM implements SpeedController {
* the deadband or inability to saturate the controller in either direction, calibration is recommended.
* The calibration procedure can be found in the VictorSP User Manual available from CTRE.
*
* - 2.037ms = full "forward"
* - 1.539ms = the "high end" of the deadband range
* - 1.513ms = center of the deadband range (off)
* - 1.487ms = the "low end" of the deadband range
* - .989ms = full "reverse"
* - 2.004ms = full "forward"
* - 1.52ms = the "high end" of the deadband range
* - 1.50ms = center of the deadband range (off)
* - 1.48ms = the "low end" of the deadband range
* - .997ms = full "reverse"
*/
protected void initVictorSP() {
setBounds(2.004, 1.52, 1.50, 1.48, .997);
@@ -43,7 +43,7 @@ public class VictorSP extends SafePWM implements SpeedController {
/**
* Constructor.
*
* @param channel The PWM channel that the VictorSP is attached to.
* @param channel The PWM channel that the VictorSP is attached to. 0-9 are on-board, 10-19 are on the MXP port
*/
public VictorSP(final int channel) {
super(channel);