mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Removed the old "parsing" interfaces
Change-Id: I94ff79f36d5b61f90c2f242fa06816bf3a3b7ac2
This commit is contained in:
@@ -11,7 +11,6 @@ import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tReso
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
|
||||
@@ -21,7 +20,7 @@ import edu.wpi.first.wpilibj.tables.ITable;
|
||||
* multiple axis and can be treated as multiple devices. Each is calibrated by finding
|
||||
* the center value over a period of time.
|
||||
*/
|
||||
public class AnalogAccelerometer extends SensorBase implements PIDSource, ISensor, LiveWindowSendable {
|
||||
public class AnalogAccelerometer extends SensorBase implements PIDSource, LiveWindowSendable {
|
||||
|
||||
private AnalogInput m_analogChannel;
|
||||
private double m_voltsPerG = 1.0;
|
||||
|
||||
@@ -16,7 +16,6 @@ import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tReso
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.AnalogJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
/**
|
||||
@@ -24,7 +23,7 @@ import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
*
|
||||
* @author dtjones
|
||||
*/
|
||||
public class AnalogTrigger implements IInputOutput {
|
||||
public class AnalogTrigger {
|
||||
|
||||
/**
|
||||
* Exceptions dealing with improper operation of the Analog trigger
|
||||
|
||||
@@ -14,23 +14,22 @@ import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tReso
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.AnalogJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
|
||||
/**
|
||||
* Class to represent a specific output from an analog trigger. This class is
|
||||
* used to get the current output value and also as a DigitalSource to provide
|
||||
* routing of an output to digital subsystems on the FPGA such as Counter,
|
||||
* Encoder, and Interrupt.
|
||||
*
|
||||
*
|
||||
* The TriggerState output indicates the primary output value of the trigger. If
|
||||
* the analog signal is less than the lower limit, the output is false. If the
|
||||
* analog value is greater than the upper limit, then the output is true. If the
|
||||
* analog value is in between, then the trigger output state maintains its most
|
||||
* recent value.
|
||||
*
|
||||
*
|
||||
* The InWindow output indicates whether or not the analog signal is inside the
|
||||
* range defined by the limits.
|
||||
*
|
||||
*
|
||||
* The RisingPulse and FallingPulse outputs detect an instantaneous transition
|
||||
* from above the upper limit to below the lower limit, and vise versa. These
|
||||
* pulses represent a rollover condition of a sensor and can be routed to an up
|
||||
@@ -46,7 +45,7 @@ import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
* rollover transition is not sharp / clean enough. Using the averaging engine
|
||||
* may help with this, but rotational speeds of the sensor will then be limited.
|
||||
*/
|
||||
public class AnalogTriggerOutput extends DigitalSource implements IInputOutput {
|
||||
public class AnalogTriggerOutput extends DigitalSource {
|
||||
|
||||
/**
|
||||
* Exceptions dealing with improper operation of the Analog trigger output
|
||||
@@ -55,7 +54,7 @@ public class AnalogTriggerOutput extends DigitalSource implements IInputOutput {
|
||||
|
||||
/**
|
||||
* Create a new exception with the given message
|
||||
*
|
||||
*
|
||||
* @param message
|
||||
* the message to pass with the exception
|
||||
*/
|
||||
@@ -71,10 +70,10 @@ public class AnalogTriggerOutput extends DigitalSource implements IInputOutput {
|
||||
/**
|
||||
* Create an object that represents one of the four outputs from an analog
|
||||
* trigger.
|
||||
*
|
||||
*
|
||||
* Because this class derives from DigitalSource, it can be passed into
|
||||
* routing functions for Counter, Encoder, etc.
|
||||
*
|
||||
*
|
||||
* @param trigger
|
||||
* The trigger for which this is an output.
|
||||
* @param outputType
|
||||
@@ -95,7 +94,7 @@ public class AnalogTriggerOutput extends DigitalSource implements IInputOutput {
|
||||
|
||||
/**
|
||||
* Get the state of the analog trigger output.
|
||||
*
|
||||
*
|
||||
* @return The state of the analog trigger output.
|
||||
*/
|
||||
public boolean get() {
|
||||
@@ -120,7 +119,7 @@ public class AnalogTriggerOutput extends DigitalSource implements IInputOutput {
|
||||
|
||||
/**
|
||||
* Request interrupts asynchronously on this digital input.
|
||||
*
|
||||
*
|
||||
* @param handler
|
||||
* the interrupt service routine
|
||||
* @param param
|
||||
|
||||
@@ -10,7 +10,6 @@ import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tReso
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
@@ -18,7 +17,7 @@ import edu.wpi.first.wpilibj.tables.ITable;
|
||||
*
|
||||
* This class allows access to the RoboRIO's internal accelerometer.
|
||||
*/
|
||||
public class BuiltInAccelerometer implements Accelerometer, ISensor, LiveWindowSendable
|
||||
public class BuiltInAccelerometer implements Accelerometer, LiveWindowSendable
|
||||
{
|
||||
/**
|
||||
* Constructor.
|
||||
|
||||
@@ -7,10 +7,9 @@ import edu.wpi.first.wpilibj.SensorBase;
|
||||
import edu.wpi.first.wpilibj.hal.CompressorJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.IDevice;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
public class Compressor extends SensorBase implements IDevice, LiveWindowSendable {
|
||||
public class Compressor extends SensorBase implements LiveWindowSendable {
|
||||
private ByteBuffer m_pcm;
|
||||
|
||||
public Compressor(int pcmId) {
|
||||
|
||||
@@ -10,13 +10,12 @@ import java.util.Stack;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
|
||||
/**
|
||||
* Pack data into the "user data" field that gets sent to the dashboard laptop
|
||||
* via the driver station.
|
||||
*/
|
||||
public class Dashboard implements IDashboard, IInputOutput {
|
||||
public class Dashboard implements IDashboard {
|
||||
|
||||
protected class MemAccess {
|
||||
|
||||
|
||||
@@ -17,7 +17,6 @@ import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.hal.InterruptJNI.InterruptHandlerFunction;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
@@ -29,8 +28,7 @@ import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
* digital inputs and outputs as required. This class is only for devices like
|
||||
* switches etc. that aren't implemented anywhere else.
|
||||
*/
|
||||
public class DigitalInput extends DigitalSource implements IInputOutput,
|
||||
LiveWindowSendable {
|
||||
public class DigitalInput extends DigitalSource implements LiveWindowSendable {
|
||||
|
||||
/**
|
||||
* Create an instance of a Digital Input class. Creates a digital input
|
||||
|
||||
@@ -20,7 +20,6 @@ import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.hal.PWMJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
@@ -29,8 +28,7 @@ import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
* devices that are implemented elsewhere will automatically allocate digital
|
||||
* inputs and outputs as required.
|
||||
*/
|
||||
public class DigitalOutput extends DigitalSource implements IInputOutput,
|
||||
LiveWindowSendable {
|
||||
public class DigitalOutput extends DigitalSource implements LiveWindowSendable {
|
||||
|
||||
private ByteBuffer m_pwmGenerator;
|
||||
|
||||
|
||||
@@ -14,12 +14,11 @@ import edu.wpi.first.wpilibj.communication.FRCCommonControlData;
|
||||
import edu.wpi.first.wpilibj.communication.FRCCommonControlMasks;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
|
||||
/**
|
||||
* Provide access to the network communication data to / from the Driver Station.
|
||||
*/
|
||||
public class DriverStation implements IInputOutput, RobotState.Interface {
|
||||
public class DriverStation implements RobotState.Interface {
|
||||
|
||||
/**
|
||||
* The size of the user status data
|
||||
@@ -135,10 +134,10 @@ public class DriverStation implements IInputOutput, RobotState.Interface {
|
||||
//m_batteryChannel = new AnalogChannel(kBatterySlot, kBatteryChannel);
|
||||
|
||||
m_packetDataAvailableSem = HALUtil.initializeMutexNormal();
|
||||
|
||||
|
||||
// set the byte order
|
||||
m_packetDataAvailableSem.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
|
||||
FRCNetworkCommunicationsLibrary.setNewDataSem(m_packetDataAvailableSem);
|
||||
|
||||
m_thread = new Thread(new DriverStationTask(this), "FRCDriverStation");
|
||||
|
||||
@@ -13,7 +13,6 @@ import java.nio.IntBuffer;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
|
||||
/**
|
||||
* Provide access to "LCD" on the Driver Station.
|
||||
@@ -22,7 +21,7 @@ import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
* Buffer the printed data locally and then send it
|
||||
* when UpdateLCD is called.
|
||||
*/
|
||||
public class DriverStationLCD extends SensorBase implements IInputOutput {
|
||||
public class DriverStationLCD extends SensorBase {
|
||||
|
||||
private static DriverStationLCD m_instance;
|
||||
/**
|
||||
|
||||
@@ -16,7 +16,6 @@ import edu.wpi.first.wpilibj.hal.EncoderJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
@@ -30,8 +29,7 @@ import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
* encoders have two digital outputs, an A Channel and a B Channel that are out
|
||||
* of phase with each other to allow the FPGA to do direction sensing.
|
||||
*/
|
||||
public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
ISensor, LiveWindowSendable {
|
||||
public class Encoder extends SensorBase implements CounterBase, PIDSource, LiveWindowSendable {
|
||||
|
||||
/**
|
||||
* The a source
|
||||
@@ -59,7 +57,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
/**
|
||||
* Common initialization code for Encoders. This code allocates resources
|
||||
* for Encoders and is common to all constructors.
|
||||
*
|
||||
*
|
||||
* @param reverseDirection
|
||||
* If true, counts down instead of up (this is all relative)
|
||||
* @param encodingType
|
||||
@@ -108,7 +106,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels.
|
||||
*
|
||||
*
|
||||
* @param aChannel
|
||||
* The a channel digital input channel.
|
||||
* @param bChannel
|
||||
@@ -130,7 +128,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels.
|
||||
*
|
||||
*
|
||||
* @param aChannel
|
||||
* The a channel digital input channel.
|
||||
* @param bChannel
|
||||
@@ -142,7 +140,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels.
|
||||
*
|
||||
*
|
||||
* @param aChannel
|
||||
* The a channel digital input channel.
|
||||
* @param bChannel
|
||||
@@ -176,7 +174,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels.
|
||||
* Using an index pulse forces 4x encoding
|
||||
*
|
||||
*
|
||||
* @param aChannel
|
||||
* The a channel digital input channel.
|
||||
* @param bChannel
|
||||
@@ -202,7 +200,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels.
|
||||
* Using an index pulse forces 4x encoding
|
||||
*
|
||||
*
|
||||
* @param aChannel
|
||||
* The a channel digital input channel.
|
||||
* @param bChannel
|
||||
@@ -220,7 +218,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* digital inputs. This is used in the case where the digital inputs are
|
||||
* shared. The Encoder class will not allocate the digital inputs and assume
|
||||
* that they already are counted.
|
||||
*
|
||||
*
|
||||
* @param aSource
|
||||
* The source that should be used for the a channel.
|
||||
* @param bSource
|
||||
@@ -249,7 +247,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* digital inputs. This is used in the case where the digital inputs are
|
||||
* shared. The Encoder class will not allocate the digital inputs and assume
|
||||
* that they already are counted.
|
||||
*
|
||||
*
|
||||
* @param aSource
|
||||
* The source that should be used for the a channel.
|
||||
* @param bSource
|
||||
@@ -264,7 +262,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* digital inputs. This is used in the case where the digital inputs are
|
||||
* shared. The Encoder class will not allocate the digital inputs and assume
|
||||
* that they already are counted.
|
||||
*
|
||||
*
|
||||
* @param aSource
|
||||
* The source that should be used for the a channel.
|
||||
* @param bSource
|
||||
@@ -305,7 +303,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* digital inputs. This is used in the case where the digital inputs are
|
||||
* shared. The Encoder class will not allocate the digital inputs and assume
|
||||
* that they already are counted.
|
||||
*
|
||||
*
|
||||
* @param aSource
|
||||
* The source that should be used for the a channel.
|
||||
* @param bSource
|
||||
@@ -338,7 +336,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* digital inputs. This is used in the case where the digital inputs are
|
||||
* shared. The Encoder class will not allocate the digital inputs and assume
|
||||
* that they already are counted.
|
||||
*
|
||||
*
|
||||
* @param aSource
|
||||
* The source that should be used for the a channel.
|
||||
* @param bSource
|
||||
@@ -413,7 +411,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
/**
|
||||
* Gets the raw value from the encoder. The raw value is the actual count
|
||||
* unscaled by the 1x, 2x, or 4x scale factor.
|
||||
*
|
||||
*
|
||||
* @return Current raw count from the encoder
|
||||
*/
|
||||
public int getRaw() {
|
||||
@@ -433,7 +431,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
/**
|
||||
* Gets the current count. Returns the current count on the Encoder. This
|
||||
* method compensates for the decoding type.
|
||||
*
|
||||
*
|
||||
* @return Current count from the Encoder adjusted for the 1x, 2x, or 4x
|
||||
* scale factor.
|
||||
*/
|
||||
@@ -461,11 +459,11 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* Returns the period of the most recent pulse. Returns the period of the
|
||||
* most recent Encoder pulse in seconds. This method compensates for the
|
||||
* decoding type.
|
||||
*
|
||||
*
|
||||
* @deprecated Use getRate() in favor of this method. This returns unscaled
|
||||
* periods and getRate() scales using value from
|
||||
* setDistancePerPulse().
|
||||
*
|
||||
*
|
||||
* @return Period in seconds of the most recent pulse.
|
||||
*/
|
||||
public double getPeriod() {
|
||||
@@ -488,8 +486,8 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* the attached device is stopped. This timeout allows users to determine if
|
||||
* the wheels or other shaft has stopped rotating. This method compensates
|
||||
* for the decoding type.
|
||||
*
|
||||
*
|
||||
*
|
||||
*
|
||||
* @param maxPeriod
|
||||
* The maximum time between rising and falling edges before the
|
||||
* FPGA will report the device stopped. This is expressed in
|
||||
@@ -512,7 +510,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* is returned that is true if the encoder is considered stopped and false
|
||||
* if it is still moving. A stopped encoder is one where the most recent
|
||||
* pulse width exceeds the MaxPeriod.
|
||||
*
|
||||
*
|
||||
* @return True if the encoder is considered stopped.
|
||||
*/
|
||||
public boolean getStopped() {
|
||||
@@ -530,7 +528,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
|
||||
/**
|
||||
* The last direction the encoder value changed.
|
||||
*
|
||||
*
|
||||
* @return The last direction the encoder value changed.
|
||||
*/
|
||||
public boolean getDirection() {
|
||||
@@ -566,7 +564,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
|
||||
/**
|
||||
* Get the distance the robot has driven since the last reset.
|
||||
*
|
||||
*
|
||||
* @return The distance driven since the last reset as scaled by the value
|
||||
* from setDistancePerPulse().
|
||||
*/
|
||||
@@ -577,7 +575,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
/**
|
||||
* Get the current rate of the encoder. Units are distance per second as
|
||||
* scaled by the value from setDistancePerPulse().
|
||||
*
|
||||
*
|
||||
* @return The current rate of the encoder.
|
||||
*/
|
||||
public double getRate() {
|
||||
@@ -587,7 +585,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
/**
|
||||
* Set the minimum rate of the device before the hardware reports it
|
||||
* stopped.
|
||||
*
|
||||
*
|
||||
* @param minRate
|
||||
* The minimum rate. The units are in distance per second as
|
||||
* scaled by the value from setDistancePerPulse().
|
||||
@@ -604,7 +602,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* encoder's rated Pulses per Revolution and factor in gearing reductions
|
||||
* following the encoder shaft. This distance can be in any units you like,
|
||||
* linear or angular.
|
||||
*
|
||||
*
|
||||
* @param distancePerPulse
|
||||
* The scale factor that will be used to convert pulses to useful
|
||||
* units.
|
||||
@@ -617,7 +615,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* Set the direction sensing for this encoder. This sets the direction
|
||||
* sensing on the encoder so that it could count in the correct software
|
||||
* direction regardless of the mounting.
|
||||
*
|
||||
*
|
||||
* @param reverseDirection
|
||||
* true if the encoder direction should be reversed
|
||||
*/
|
||||
@@ -634,10 +632,10 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* timer to average when calculating the period. Perform averaging to
|
||||
* account for mechanical imperfections or as oversampling to increase
|
||||
* resolution.
|
||||
*
|
||||
*
|
||||
* TODO: Should this throw a checked exception, so that the user has to deal
|
||||
* with giving an incorrect value?
|
||||
*
|
||||
*
|
||||
* @param samplesToAverage
|
||||
* The number of samples to average from 1 to 127.
|
||||
*/
|
||||
@@ -666,7 +664,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
* timer to average when calculating the period. Perform averaging to
|
||||
* account for mechanical imperfections or as oversampling to increase
|
||||
* resolution.
|
||||
*
|
||||
*
|
||||
* @return SamplesToAverage The number of samples being averaged (from 1 to
|
||||
* 127)
|
||||
*/
|
||||
@@ -689,7 +687,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
/**
|
||||
* Set which parameter of the encoder you are using as a process control
|
||||
* variable. The encoder class supports the rate and distance parameters.
|
||||
*
|
||||
*
|
||||
* @param pidSource
|
||||
* An enum to select the parameter.
|
||||
*/
|
||||
@@ -700,7 +698,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
|
||||
/**
|
||||
* Implement the PIDSource interface.
|
||||
*
|
||||
*
|
||||
* @return The current value of the selected source parameter.
|
||||
*/
|
||||
public double pidGet() {
|
||||
|
||||
@@ -10,7 +10,6 @@ package edu.wpi.first.wpilibj;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
|
||||
/**
|
||||
* Alias for counter class.
|
||||
@@ -18,7 +17,7 @@ import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
* the gear tooth sensor, but in future versions we might implement the necessary timing in the
|
||||
* FPGA to sense direction.
|
||||
*/
|
||||
public class GearTooth extends Counter implements ISensor {
|
||||
public class GearTooth extends Counter {
|
||||
|
||||
private static final double kGearToothThreshold = 55e-6;
|
||||
|
||||
|
||||
@@ -11,7 +11,6 @@ import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
@@ -24,8 +23,7 @@ import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
* determine the default offset. This is subtracted from each sample to
|
||||
* determine the heading.
|
||||
*/
|
||||
public class Gyro extends SensorBase implements PIDSource, ISensor,
|
||||
LiveWindowSendable {
|
||||
public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable {
|
||||
|
||||
static final int kOversampleBits = 10;
|
||||
static final int kAverageBits = 0;
|
||||
|
||||
@@ -10,12 +10,11 @@ package edu.wpi.first.wpilibj;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.parsing.IDeviceController;
|
||||
|
||||
/**
|
||||
* Texas Instruments Jaguar Speed Controller as a PWM device.
|
||||
*/
|
||||
public class Jaguar extends SafePWM implements SpeedController, IDeviceController {
|
||||
public class Jaguar extends SafePWM implements SpeedController {
|
||||
|
||||
/**
|
||||
* Common initialization code called by all constructors.
|
||||
|
||||
@@ -8,7 +8,6 @@ package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
|
||||
/**
|
||||
* Handle input from standard Joysticks connected to the Driver Station.
|
||||
@@ -16,7 +15,7 @@ import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
* the most recent value is returned. There is a single class instance for each joystick and the mapping
|
||||
* of ports to hardware buttons depends on the code in the driver station.
|
||||
*/
|
||||
public class Joystick extends GenericHID implements IInputOutput {
|
||||
public class Joystick extends GenericHID {
|
||||
|
||||
static final byte kDefaultXAxis = 1;
|
||||
static final byte kDefaultYAxis = 2;
|
||||
|
||||
@@ -17,7 +17,6 @@ import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.hal.RelayJNI;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.IDeviceController;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
@@ -33,9 +32,8 @@ import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
* allows the two channels (forward and reverse) to be used independently for
|
||||
* something that does not care about voltage polarity (like a solenoid).
|
||||
*/
|
||||
public class Relay extends SensorBase implements IDeviceController,
|
||||
LiveWindowSendable {
|
||||
|
||||
public class Relay extends SensorBase implements LiveWindowSendable {
|
||||
|
||||
/**
|
||||
* This class represents errors in trying to set relay values contradictory
|
||||
* to the direction to which the relay is set.
|
||||
@@ -73,12 +71,12 @@ public class Relay extends SensorBase implements IDeviceController,
|
||||
* value: reverse
|
||||
*/
|
||||
kReverse(3);
|
||||
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
|
||||
|
||||
private Value(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
@@ -106,11 +104,11 @@ public class Relay extends SensorBase implements IDeviceController,
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
|
||||
|
||||
private Direction(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
private final int m_channel;
|
||||
@@ -185,7 +183,7 @@ public class Relay extends SensorBase implements IDeviceController,
|
||||
if (m_direction == Direction.kBoth || m_direction == Direction.kReverse) {
|
||||
relayChannels.free(m_channel*2 + 1);
|
||||
}
|
||||
|
||||
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
|
||||
@@ -10,7 +10,6 @@ import edu.wpi.first.wpilibj.can.CANNotInitializedException;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.parsing.IUtility;
|
||||
|
||||
/**
|
||||
* Utility class for handling Robot drive based on a definition of the motor configuration.
|
||||
@@ -20,7 +19,7 @@ import edu.wpi.first.wpilibj.parsing.IUtility;
|
||||
* used for either the drive function (intended for hand created drive code, such as autonomous)
|
||||
* or with the Tank/Arcade functions intended to be used for Operator Control driving.
|
||||
*/
|
||||
public class RobotDrive implements MotorSafety, IUtility {
|
||||
public class RobotDrive implements MotorSafety {
|
||||
|
||||
protected MotorSafetyHelper m_safetyHelper;
|
||||
|
||||
|
||||
@@ -10,7 +10,6 @@ package edu.wpi.first.wpilibj;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.parsing.IDevice;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
@@ -20,7 +19,7 @@ import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
* The range parameters default to the appropriate values for the Hitec HS-322HD servo provided
|
||||
* in the FIRST Kit of Parts in 2008.
|
||||
*/
|
||||
public class Servo extends PWM implements IDevice {
|
||||
public class Servo extends PWM {
|
||||
|
||||
private static final double kMaxServoAngle = 180.0;
|
||||
private static final double kMinServoAngle = 0.0;
|
||||
|
||||
@@ -11,13 +11,12 @@ import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.parsing.IDeviceController;
|
||||
|
||||
/**
|
||||
* SolenoidBase class is the common base class for the Solenoid and
|
||||
* DoubleSolenoid classes.
|
||||
*/
|
||||
public abstract class SolenoidBase extends SensorBase implements IDeviceController {
|
||||
public abstract class SolenoidBase extends SensorBase {
|
||||
|
||||
private ByteBuffer[] m_ports;
|
||||
protected int m_moduleNumber; ///< The number of the solenoid module being used.
|
||||
|
||||
@@ -10,12 +10,11 @@ package edu.wpi.first.wpilibj;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.parsing.IDeviceController;
|
||||
|
||||
/**
|
||||
* CTRE Talon Speed Controller
|
||||
*/
|
||||
public class Talon extends SafePWM implements SpeedController, IDeviceController {
|
||||
public class Talon extends SafePWM implements SpeedController {
|
||||
|
||||
/**
|
||||
* Common initialization code called by all constructors.
|
||||
|
||||
@@ -12,7 +12,6 @@ import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
@@ -25,8 +24,7 @@ import edu.wpi.first.wpilibj.tables.ITable;
|
||||
* and goes low when the echo is received. The time that the line is high
|
||||
* determines the round trip distance (time of flight).
|
||||
*/
|
||||
public class Ultrasonic extends SensorBase implements PIDSource, ISensor,
|
||||
LiveWindowSendable {
|
||||
public class Ultrasonic extends SensorBase implements PIDSource, LiveWindowSendable {
|
||||
|
||||
/**
|
||||
* The units to return when PIDGet is called
|
||||
|
||||
@@ -13,12 +13,11 @@ import java.nio.IntBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.hal.HALLibrary;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.parsing.IUtility;
|
||||
|
||||
/**
|
||||
* Contains global utility functions
|
||||
*/
|
||||
public class Utility implements IUtility {
|
||||
public class Utility {
|
||||
|
||||
private Utility() {
|
||||
}
|
||||
|
||||
@@ -10,12 +10,11 @@ package edu.wpi.first.wpilibj;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.parsing.IDeviceController;
|
||||
|
||||
/**
|
||||
* VEX Robotics Victor Speed Controller
|
||||
*/
|
||||
public class Victor extends SafePWM implements SpeedController, IDeviceController {
|
||||
public class Victor extends SafePWM implements SpeedController {
|
||||
|
||||
/**
|
||||
* Common initialization code called by all constructors.
|
||||
|
||||
@@ -17,7 +17,6 @@ import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.image.ColorImage;
|
||||
import edu.wpi.first.wpilibj.image.HSLImage;
|
||||
import edu.wpi.first.wpilibj.image.NIVisionException;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
//TODO figure out where to use finally to free resources
|
||||
@@ -30,7 +29,7 @@ import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
* This class is a singleton used to configure and get images from the axis camera.
|
||||
* @author dtjones
|
||||
*/
|
||||
public class AxisCamera implements ISensor {
|
||||
public class AxisCamera {
|
||||
|
||||
private static AxisCamera m_instance = null;
|
||||
|
||||
|
||||
@@ -10,7 +10,6 @@ package edu.wpi.first.wpilibj.internal;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.Utility;
|
||||
import edu.wpi.first.wpilibj.parsing.IUtility;
|
||||
|
||||
/**
|
||||
* Timer objects measure accumulated time in milliseconds.
|
||||
@@ -19,7 +18,7 @@ import edu.wpi.first.wpilibj.parsing.IUtility;
|
||||
* value. The implementation simply records the time when started and subtracts the current time
|
||||
* whenever the value is requested.
|
||||
*/
|
||||
public class HardwareTimer implements IUtility, Timer.StaticInterface {
|
||||
public class HardwareTimer implements Timer.StaticInterface {
|
||||
/**
|
||||
* Pause the thread for a specified time. Pause the execution of the
|
||||
* thread for a specified period of time given in seconds. Motors will
|
||||
@@ -62,7 +61,7 @@ public class HardwareTimer implements IUtility, Timer.StaticInterface {
|
||||
private long m_startTime;
|
||||
private double m_accumulatedTime;
|
||||
private boolean m_running;
|
||||
|
||||
|
||||
/**
|
||||
* Create a new timer object.
|
||||
* Create a new timer object and reset the time to zero. The timer is initially not running and
|
||||
@@ -71,11 +70,11 @@ public class HardwareTimer implements IUtility, Timer.StaticInterface {
|
||||
public TimerImpl() {
|
||||
reset();
|
||||
}
|
||||
|
||||
|
||||
private long getMsClock() {
|
||||
return Utility.getFPGATime() / 1000;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the current time from the timer. If the clock is running it is derived from
|
||||
* the current system clock the start time stored in the timer class. If the clock
|
||||
@@ -90,7 +89,7 @@ public class HardwareTimer implements IUtility, Timer.StaticInterface {
|
||||
return m_accumulatedTime;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Reset the timer by setting the time to 0.
|
||||
* Make the timer startTime the current time so new requests will be relative now
|
||||
@@ -99,7 +98,7 @@ public class HardwareTimer implements IUtility, Timer.StaticInterface {
|
||||
m_accumulatedTime = 0;
|
||||
m_startTime = getMsClock();
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Start the timer running.
|
||||
* Just set the running flag to true indicating that all time requests should be
|
||||
@@ -109,7 +108,7 @@ public class HardwareTimer implements IUtility, Timer.StaticInterface {
|
||||
m_startTime = getMsClock();
|
||||
m_running = true;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Stop the timer.
|
||||
* This computes the time as of now and clears the running flag, causing all
|
||||
|
||||
Reference in New Issue
Block a user