mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[hal,wpilib] Remove a ton of things related to the FPGA (#7846)
Co-authored-by: Gold856 <117957790+Gold856@users.noreply.github.com>
This commit is contained in:
@@ -56,22 +56,7 @@ public class AnalogInput implements Sendable, AutoCloseable {
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a sample from the output of the oversample and average engine for 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^(OversampleBits + AverageBits) samples have
|
||||
* been acquired from this channel. Use getAverageVoltage() to get the analog value in calibrated
|
||||
* units.
|
||||
*
|
||||
* @return A sample from the oversample and average engine for this channel.
|
||||
*/
|
||||
public int getAverageValue() {
|
||||
return AnalogInputJNI.getAnalogAverageValue(m_port);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a scaled sample straight from this channel. The value is scaled to units of Volts using the
|
||||
* calibrated scaling data from getLSBWeight() and getOffset().
|
||||
* Get a scaled sample straight from this channel. The value is scaled to units of Volts.
|
||||
*
|
||||
* @return A scaled sample straight from this channel.
|
||||
*/
|
||||
@@ -79,43 +64,6 @@ public class AnalogInput implements Sendable, AutoCloseable {
|
||||
return AnalogInputJNI.getAnalogVoltage(m_port);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a scaled sample from the output of the oversample and average engine for this channel. The
|
||||
* value is scaled to units of Volts using the calibrated scaling data from getLSBWeight() and
|
||||
* getOffset(). Using oversampling will cause this value to be higher resolution, but it will
|
||||
* update more slowly. Using averaging will cause this value to be more stable, but it will update
|
||||
* more slowly.
|
||||
*
|
||||
* @return A scaled sample from the output of the oversample and average engine for this channel.
|
||||
*/
|
||||
public double getAverageVoltage() {
|
||||
return AnalogInputJNI.getAnalogAverageVoltage(m_port);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the factory scaling the least significant bit weight constant. The least significant bit
|
||||
* weight constant for the channel that was calibrated in manufacturing and stored in an eeprom.
|
||||
*
|
||||
* <p>Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
|
||||
*
|
||||
* @return Least significant bit weight.
|
||||
*/
|
||||
public long getLSBWeight() {
|
||||
return AnalogInputJNI.getAnalogLSBWeight(m_port);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the factory scaling offset constant. The offset constant for the channel that was
|
||||
* calibrated in manufacturing and stored in an eeprom.
|
||||
*
|
||||
* <p>Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
|
||||
*
|
||||
* @return Offset constant.
|
||||
*/
|
||||
public int getOffset() {
|
||||
return AnalogInputJNI.getAnalogOffset(m_port);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the channel number.
|
||||
*
|
||||
@@ -125,70 +73,6 @@ public class AnalogInput implements Sendable, AutoCloseable {
|
||||
return m_channel;
|
||||
}
|
||||
|
||||
/**
|
||||
* 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 automatically in the FPGA.
|
||||
*
|
||||
* @param bits The number of averaging bits.
|
||||
*/
|
||||
public void setAverageBits(final int bits) {
|
||||
AnalogInputJNI.setAnalogAverageBits(m_port, bits);
|
||||
}
|
||||
|
||||
/**
|
||||
* 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 averaging is done automatically in the FPGA.
|
||||
*
|
||||
* @return The number of averaging bits.
|
||||
*/
|
||||
public int getAverageBits() {
|
||||
return AnalogInputJNI.getAnalogAverageBits(m_port);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the number of oversample bits. This sets the number of oversample bits. The actual number
|
||||
* of oversampled values is 2^bits. The oversampling is done automatically in the FPGA.
|
||||
*
|
||||
* @param bits The number of oversample bits.
|
||||
*/
|
||||
public void setOversampleBits(final int bits) {
|
||||
AnalogInputJNI.setAnalogOversampleBits(m_port, bits);
|
||||
}
|
||||
|
||||
/**
|
||||
* 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. The oversampling is done automatically in the
|
||||
* FPGA.
|
||||
*
|
||||
* @return The number of oversample bits.
|
||||
*/
|
||||
public int getOversampleBits() {
|
||||
return AnalogInputJNI.getAnalogOversampleBits(m_port);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the sample rate per channel.
|
||||
*
|
||||
* <p>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) {
|
||||
AnalogInputJNI.setAnalogSampleRate(samplesPerSecond);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current sample rate.
|
||||
*
|
||||
* <p>This assumes one entry in the scan list. This is a global setting for all channels.
|
||||
*
|
||||
* @return Sample rate.
|
||||
*/
|
||||
public static double getGlobalSampleRate() {
|
||||
return AnalogInputJNI.getAnalogSampleRate();
|
||||
}
|
||||
|
||||
/**
|
||||
* Indicates this input is used by a simulated device.
|
||||
*
|
||||
@@ -201,6 +85,6 @@ public class AnalogInput implements Sendable, AutoCloseable {
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
builder.setSmartDashboardType("Analog Input");
|
||||
builder.addDoubleProperty("Value", this::getAverageVoltage, null);
|
||||
builder.addDoubleProperty("Value", this::getVoltage, null);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,7 +7,6 @@ package org.wpilib.hardware.discrete;
|
||||
import org.wpilib.hardware.hal.DIOJNI;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.SimDevice;
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
@@ -29,7 +28,6 @@ public class DigitalInput implements AutoCloseable, Sendable {
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public DigitalInput(int channel) {
|
||||
SensorUtil.checkDigitalChannel(channel);
|
||||
m_channel = channel;
|
||||
|
||||
m_handle = DIOJNI.initializeDIOPort(channel, true);
|
||||
|
||||
@@ -7,7 +7,6 @@ package org.wpilib.hardware.discrete;
|
||||
import org.wpilib.hardware.hal.DIOJNI;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.SimDevice;
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
@@ -30,7 +29,6 @@ public class DigitalOutput implements AutoCloseable, Sendable {
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public DigitalOutput(int channel) {
|
||||
SensorUtil.checkDigitalChannel(channel);
|
||||
m_channel = channel;
|
||||
|
||||
m_handle = DIOJNI.initializeDIOPort(channel, false);
|
||||
@@ -161,8 +159,6 @@ public class DigitalOutput implements AutoCloseable, Sendable {
|
||||
if (m_pwmGenerator == invalidPwmGenerator) {
|
||||
return;
|
||||
}
|
||||
// Disable the output by routing to a dead bit.
|
||||
DIOJNI.setDigitalPWMOutputChannel(m_pwmGenerator, SensorUtil.NUM_DIGITAL_CHANNELS);
|
||||
DIOJNI.freeDigitalPWM(m_pwmGenerator);
|
||||
m_pwmGenerator = invalidPwmGenerator;
|
||||
}
|
||||
|
||||
@@ -7,7 +7,6 @@ package org.wpilib.hardware.discrete;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.PWMJNI;
|
||||
import org.wpilib.hardware.hal.SimDevice;
|
||||
import org.wpilib.system.SensorUtil;
|
||||
import org.wpilib.util.sendable.Sendable;
|
||||
import org.wpilib.util.sendable.SendableBuilder;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
@@ -46,7 +45,6 @@ public class PWM implements Sendable, AutoCloseable {
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public PWM(final int channel, final boolean registerSendable) {
|
||||
SensorUtil.checkPWMChannel(channel);
|
||||
m_channel = channel;
|
||||
|
||||
m_handle = PWMJNI.initializePWMPort(channel);
|
||||
|
||||
@@ -60,67 +60,6 @@ public class AnalogInputSim {
|
||||
AnalogInDataJNI.setInitialized(m_index, initialized);
|
||||
}
|
||||
|
||||
/**
|
||||
* Register a callback on the number of average bits.
|
||||
*
|
||||
* @param callback the callback that will be called whenever the number of average bits is changed
|
||||
* @param initialNotify if true, the callback will be run on the initial value
|
||||
* @return the {@link CallbackStore} object associated with this callback.
|
||||
*/
|
||||
public CallbackStore registerAverageBitsCallback(NotifyCallback callback, boolean initialNotify) {
|
||||
int uid = AnalogInDataJNI.registerAverageBitsCallback(m_index, callback, initialNotify);
|
||||
return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelAverageBitsCallback);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the number of average bits.
|
||||
*
|
||||
* @return the number of average bits
|
||||
*/
|
||||
public int getAverageBits() {
|
||||
return AnalogInDataJNI.getAverageBits(m_index);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the number of average bits.
|
||||
*
|
||||
* @param averageBits the new value
|
||||
*/
|
||||
public void setAverageBits(int averageBits) {
|
||||
AnalogInDataJNI.setAverageBits(m_index, averageBits);
|
||||
}
|
||||
|
||||
/**
|
||||
* Register a callback on the amount of oversampling bits.
|
||||
*
|
||||
* @param callback the callback that will be called whenever the oversampling bits are changed.
|
||||
* @param initialNotify if true, the callback will be run on the initial value
|
||||
* @return the {@link CallbackStore} object associated with this callback.
|
||||
*/
|
||||
public CallbackStore registerOversampleBitsCallback(
|
||||
NotifyCallback callback, boolean initialNotify) {
|
||||
int uid = AnalogInDataJNI.registerOversampleBitsCallback(m_index, callback, initialNotify);
|
||||
return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelOversampleBitsCallback);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the amount of oversampling bits.
|
||||
*
|
||||
* @return the amount of oversampling bits
|
||||
*/
|
||||
public int getOversampleBits() {
|
||||
return AnalogInDataJNI.getOversampleBits(m_index);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the amount of oversampling bits.
|
||||
*
|
||||
* @param oversampleBits the new value
|
||||
*/
|
||||
public void setOversampleBits(int oversampleBits) {
|
||||
AnalogInDataJNI.setOversampleBits(m_index, oversampleBits);
|
||||
}
|
||||
|
||||
/**
|
||||
* Register a callback on the voltage.
|
||||
*
|
||||
|
||||
@@ -8,14 +8,10 @@ import org.wpilib.hardware.hal.HALUtil;
|
||||
|
||||
/** Runtime type. */
|
||||
public enum RuntimeType {
|
||||
/** roboRIO 1.0. */
|
||||
ROBORIO(HALUtil.RUNTIME_ROBORIO),
|
||||
/** roboRIO 2.0. */
|
||||
ROBORIO_2(HALUtil.RUNTIME_ROBORIO_2),
|
||||
/** Systemcore runtime. */
|
||||
SYSTEMCORE(HALUtil.RUNTIME_SYSTEMCORE),
|
||||
/** Simulation runtime. */
|
||||
SIMULATION(HALUtil.RUNTIME_SIMULATION),
|
||||
/** Systemcore. */
|
||||
SYSTEMCORE(HALUtil.RUNTIME_SYSTEMCORE);
|
||||
SIMULATION(HALUtil.RUNTIME_SIMULATION);
|
||||
|
||||
/** RuntimeType value. */
|
||||
public final int value;
|
||||
@@ -31,11 +27,10 @@ public enum RuntimeType {
|
||||
* @return Matching runtime type
|
||||
*/
|
||||
public static RuntimeType getValue(int type) {
|
||||
return switch (type) {
|
||||
case HALUtil.RUNTIME_ROBORIO -> RuntimeType.ROBORIO;
|
||||
case HALUtil.RUNTIME_ROBORIO_2 -> RuntimeType.ROBORIO_2;
|
||||
case HALUtil.RUNTIME_SYSTEMCORE -> RuntimeType.SYSTEMCORE;
|
||||
default -> RuntimeType.SIMULATION;
|
||||
};
|
||||
if (type == HALUtil.RUNTIME_SYSTEMCORE) {
|
||||
return RuntimeType.SYSTEMCORE;
|
||||
} else {
|
||||
return RuntimeType.SIMULATION;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -4,10 +4,6 @@
|
||||
|
||||
package org.wpilib.system;
|
||||
|
||||
import org.wpilib.hardware.hal.AnalogInputJNI;
|
||||
import org.wpilib.hardware.hal.ConstantsJNI;
|
||||
import org.wpilib.hardware.hal.DIOJNI;
|
||||
import org.wpilib.hardware.hal.PWMJNI;
|
||||
import org.wpilib.hardware.hal.PortsJNI;
|
||||
|
||||
/**
|
||||
@@ -15,22 +11,12 @@ import org.wpilib.hardware.hal.PortsJNI;
|
||||
* channels and error processing.
|
||||
*/
|
||||
public final class SensorUtil {
|
||||
/** Ticks per microsecond. */
|
||||
public static final int SYSTEM_CLOCK_TICKS_PER_MICROSECOND =
|
||||
ConstantsJNI.getSystemClockTicksPerMicrosecond();
|
||||
|
||||
/** Number of digital channels per Systemcore. */
|
||||
public static final int NUM_DIGITAL_CHANNELS = PortsJNI.getNumDigitalChannels();
|
||||
|
||||
/** Number of analog input channels per Systemcore. */
|
||||
public static final int NUM_ANALOG_INPUTS = PortsJNI.getNumAnalogInputs();
|
||||
/** Number of SmartIo Ports. */
|
||||
public static final int kSmartIoPorts = PortsJNI.getNumSmartIo();
|
||||
|
||||
/** Number of solenoid channels per module. */
|
||||
public static final int NUM_CTRE_SOLENOID_CHANNELS = PortsJNI.getNumCTRESolenoidChannels();
|
||||
|
||||
/** Number of PWM channels per Systemcore. */
|
||||
public static final int NUM_PWM_CHANNELS = PortsJNI.getNumPWMChannels();
|
||||
|
||||
/** Number of power distribution channels per PDP. */
|
||||
public static final int NUM_CTRE_PDP_CHANNELS = PortsJNI.getNumCTREPDPChannels();
|
||||
|
||||
@@ -46,57 +32,6 @@ public final class SensorUtil {
|
||||
/** Number of PH modules. */
|
||||
public static final int NUM_REV_PH_MODULES = PortsJNI.getNumREVPHModules();
|
||||
|
||||
/**
|
||||
* Check that the digital channel number is valid. Verify that the channel number is one of the
|
||||
* legal channel numbers. Channel numbers are 0-based.
|
||||
*
|
||||
* @param channel The channel number to check.
|
||||
*/
|
||||
public static void checkDigitalChannel(final int channel) {
|
||||
if (!DIOJNI.checkDIOChannel(channel)) {
|
||||
String buf =
|
||||
"Requested DIO channel is out of range. Minimum: 0, Maximum: "
|
||||
+ NUM_DIGITAL_CHANNELS
|
||||
+ ", Requested: "
|
||||
+ channel;
|
||||
throw new IllegalArgumentException(buf);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check that the PWM channel number is valid. Verify that the channel number is one of the legal
|
||||
* channel numbers. Channel numbers are 0-based.
|
||||
*
|
||||
* @param channel The channel number to check.
|
||||
*/
|
||||
public static void checkPWMChannel(final int channel) {
|
||||
if (!PWMJNI.checkPWMChannel(channel)) {
|
||||
String buf =
|
||||
"Requested PWM channel is out of range. Minimum: 0, Maximum: "
|
||||
+ NUM_PWM_CHANNELS
|
||||
+ ", Requested: "
|
||||
+ channel;
|
||||
throw new IllegalArgumentException(buf);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check that the analog input number is value. Verify that the analog input number is one of the
|
||||
* legal channel numbers. Channel numbers are 0-based.
|
||||
*
|
||||
* @param channel The channel number to check.
|
||||
*/
|
||||
public static void checkAnalogInputChannel(final int channel) {
|
||||
if (!AnalogInputJNI.checkAnalogInputChannel(channel)) {
|
||||
String buf =
|
||||
"Requested analog input channel is out of range. Minimum: 0, Maximum: "
|
||||
+ NUM_ANALOG_INPUTS
|
||||
+ ", Requested: "
|
||||
+ channel;
|
||||
throw new IllegalArgumentException(buf);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the number of the default solenoid module.
|
||||
*
|
||||
|
||||
@@ -52,13 +52,4 @@ class AnalogInputSimTest {
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void testSetOverSampleBits() {
|
||||
HAL.initialize(500, 0);
|
||||
try (AnalogInput input = new AnalogInput(5)) {
|
||||
input.setOversampleBits(3504);
|
||||
assertEquals(3504, input.getOversampleBits());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -5,26 +5,10 @@
|
||||
package org.wpilib.system;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertThrows;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class SensorUtilTest {
|
||||
@Test
|
||||
void checkAnalogInputChannel() {
|
||||
assertThrows(IllegalArgumentException.class, () -> SensorUtil.checkAnalogInputChannel(100));
|
||||
}
|
||||
|
||||
@Test
|
||||
void testInvalidDigitalChannel() {
|
||||
assertThrows(IllegalArgumentException.class, () -> SensorUtil.checkDigitalChannel(100));
|
||||
}
|
||||
|
||||
@Test
|
||||
void testInvalidPwmChannel() {
|
||||
assertThrows(IllegalArgumentException.class, () -> SensorUtil.checkPWMChannel(100));
|
||||
}
|
||||
|
||||
@Test
|
||||
void testgetDefaultCtrePcmModule() {
|
||||
assertEquals(0, SensorUtil.getDefaultCTREPCMModule());
|
||||
|
||||
Reference in New Issue
Block a user