[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:
Thad House
2026-04-17 19:38:25 -07:00
committed by GitHub
parent fdb454a6b1
commit 6cb6903780
73 changed files with 69 additions and 1834 deletions

View File

@@ -55,77 +55,6 @@ public class AnalogInputJNI extends JNIWrapper {
*/ */
public static native void setAnalogInputSimDevice(int handle, int device); public static native void setAnalogInputSimDevice(int handle, int device);
/**
* Sets the sample rate.
*
* <p>This is a global setting for the Athena and effects all channels.
*
* @param samplesPerSecond The number of samples per channel per second.
* @see "HAL_SetAnalogSampleRate"
*/
public static native void setAnalogSampleRate(double samplesPerSecond);
/**
* Gets the current sample rate.
*
* <p>This assumes one entry in the scan list. This is a global setting for the Athena and effects
* all channels.
*
* @return Sample rate.
* @see "HAL_GetAnalogSampleRate"
*/
public static native double getAnalogSampleRate();
/**
* Sets the number of averaging bits.
*
* <p>This sets the number of averaging bits. The actual number of averaged samples is 2**bits.
* Use averaging to improve the stability of your measurement at the expense of sampling rate. The
* averaging is done automatically in the FPGA.
*
* @param analogPortHandle Handle to the analog port to configure.
* @param bits Number of bits to average.
* @see "HAL_SetAnalogAverageBits"
*/
public static native void setAnalogAverageBits(int analogPortHandle, int bits);
/**
* Gets the number of averaging bits.
*
* <p>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.
*
* @param analogPortHandle Handle to the analog port to use.
* @return Bits to average.
* @see "HAL_GetAnalogAverageBits"
*/
public static native int getAnalogAverageBits(int analogPortHandle);
/**
* Sets the number of oversample bits.
*
* <p>This sets the number of oversample bits. The actual number of oversampled values is 2**bits.
* Use oversampling to improve the resolution of your measurements at the expense of sampling
* rate. The oversampling is done automatically in the FPGA.
*
* @param analogPortHandle Handle to the analog port to use.
* @param bits Number of bits to oversample.
* @see "HAL_SetAnalogOversampleBits"
*/
public static native void setAnalogOversampleBits(int analogPortHandle, int bits);
/**
* Gets the number of oversample bits.
*
* <p>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.
*
* @param analogPortHandle Handle to the analog port to use.
* @return Bits to oversample.
* @see "HAL_GetAnalogOversampleBits"
*/
public static native int getAnalogOversampleBits(int analogPortHandle);
/** /**
* Gets a sample straight from the channel on this module. * Gets a sample straight from the channel on this module.
* *
@@ -139,21 +68,6 @@ public class AnalogInputJNI extends JNIWrapper {
*/ */
public static native short getAnalogValue(int analogPortHandle); public static native short getAnalogValue(int analogPortHandle);
/**
* Gets a sample from the output of the oversample and average engine for the channel.
*
* <p>The sample is 12-bit + the value 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 the module on this channel. Use GetAverageVoltage() to get the analog value
* in calibrated units.
*
* @param analogPortHandle Handle to the analog port to use.
* @return A sample from the oversample and average engine for the channel.
* @see "HAL_GetAnalogAverageValue"
*/
public static native int getAnalogAverageValue(int analogPortHandle);
/** /**
* Converts a voltage to a raw value for a specified channel. * Converts a voltage to a raw value for a specified channel.
* *
@@ -181,8 +95,7 @@ public class AnalogInputJNI extends JNIWrapper {
/** /**
* Gets a scaled sample straight from the channel on this module. * Gets a scaled sample straight from the channel on this module.
* *
* <p>The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() * <p>The value is scaled to units of Volts.
* and GetOffset().
* *
* @param analogPortHandle Handle to the analog port to use. * @param analogPortHandle Handle to the analog port to use.
* @return A scaled sample straight from the channel on this module. * @return A scaled sample straight from the channel on this module.
@@ -190,45 +103,6 @@ public class AnalogInputJNI extends JNIWrapper {
*/ */
public static native double getAnalogVoltage(int analogPortHandle); public static native double getAnalogVoltage(int analogPortHandle);
/**
* Gets a scaled sample from the output of the oversample and average engine for the channel.
*
* <p>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.
*
* @param analogPortHandle Handle to the analog port to use.
* @return A scaled sample from the output of the oversample and average engine for the channel.
* @see "HAL_GetAnalogAverageVoltage"
*/
public static native double getAnalogAverageVoltage(int analogPortHandle);
/**
* Gets the factory scaling least significant bit weight constant. The least significant bit
* weight constant for the channel that was calibrated in manufacturing and stored in an eeprom in
* the module.
*
* <p>Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
*
* @param analogPortHandle Handle to the analog port to use.
* @return Least significant bit weight.
* @see "HAL_GetAnalogLSBWeight"
*/
public static native int getAnalogLSBWeight(int analogPortHandle);
/**
* Gets the factory scaling offset constant. The offset constant for the channel that was
* calibrated in manufacturing and stored in an eeprom in the module.
*
* <p>Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
*
* @param analogPortHandle Handle to the analog port to use.
* @return Offset constant.
* @see "HAL_GetAnalogOffset"
*/
public static native int getAnalogOffset(int analogPortHandle);
/** Utility class. */ /** Utility class. */
private AnalogInputJNI() {} private AnalogInputJNI() {}
} }

View File

@@ -1,23 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package org.wpilib.hardware.hal;
/**
* Constants HAL JNI functions.
*
* @see "wpi/hal/Constants.h"
*/
public class ConstantsJNI extends JNIWrapper {
/**
* Gets the number of FPGA system clock ticks per microsecond.
*
* @return the number of clock ticks per microsecond
* @see "HAL_GetSystemClockTicksPerMicrosecond"
*/
public static native int getSystemClockTicksPerMicrosecond();
/** Utility class. */
private ConstantsJNI() {}
}

View File

@@ -25,17 +25,11 @@ public final class HALUtil extends JNIWrapper {
/** A parameter is out of range. */ /** A parameter is out of range. */
public static final int PARAMETER_OUT_OF_RANGE = -1028; public static final int PARAMETER_OUT_OF_RANGE = -1028;
/** roboRIO 1.0. */ /** Systemcore runtime. */
public static final int RUNTIME_ROBORIO = 0; public static final int RUNTIME_SYSTEMCORE = 0;
/** roboRIO 2.0. */
public static final int RUNTIME_ROBORIO_2 = 1;
/** Simulation runtime. */ /** Simulation runtime. */
public static final int RUNTIME_SIMULATION = 2; public static final int RUNTIME_SIMULATION = 1;
/** Systemcore. */
public static final int RUNTIME_SYSTEMCORE = 3;
/** /**
* Returns the roboRIO serial number. * Returns the roboRIO serial number.
@@ -72,9 +66,8 @@ public final class HALUtil extends JNIWrapper {
* Returns the runtime type of the HAL. * Returns the runtime type of the HAL.
* *
* @return HAL Runtime Type * @return HAL Runtime Type
* @see RUNTIME_ROBORIO * @see #RUNTIME_SYSTEMCORE
* @see RUNTIME_ROBORIO_2 * @see #RUNTIME_SIMULATION
* @see RUNTIME_SIMULATION
* @see "HAL_GetRuntimeType" * @see "HAL_GetRuntimeType"
*/ */
public static native int getHALRuntimeType(); public static native int getHALRuntimeType();

View File

@@ -19,60 +19,12 @@ public class PortsJNI extends JNIWrapper {
public static native int getNumCanBuses(); public static native int getNumCanBuses();
/** /**
* Gets the number of analog inputs in the current system. * Gets the number of SmartIo ports in the current system.
* *
* @return the number of analog inputs * @return the number of SmartIo
* @see "HAL_GetNumAnalogInputs" * @see "HAL_GetNumSmartIo"
*/ */
public static native int getNumAnalogInputs(); public static native int getNumSmartIo();
/**
* Gets the number of counters in the current system.
*
* @return the number of counters
* @see "HAL_GetNumCounters"
*/
public static native int getNumCounters();
/**
* Gets the number of digital channels in the current system.
*
* @return the number of digital channels
* @see "HAL_GetNumDigitalChannels"
*/
public static native int getNumDigitalChannels();
/**
* Gets the number of PWM channels in the current system.
*
* @return the number of PWM channels
* @see "HAL_GetNumPWMChannels"
*/
public static native int getNumPWMChannels();
/**
* Gets the number of digital IO PWM outputs in the current system.
*
* @return the number of digital IO PWM outputs
* @see "HAL_GetNumDigitalPWMOutputs"
*/
public static native int getNumDigitalPWMOutputs();
/**
* Gets the number of quadrature encoders in the current system.
*
* @return the number of quadrature encoders
* @see "HAL_GetNumEncoders"
*/
public static native int getNumEncoders();
/**
* Gets the number of interrupts in the current system.
*
* @return the number of interrupts
* @see "HAL_GetNumInterrupts"
*/
public static native int getNumInterrupts();
/** /**
* Gets the number of PCM modules in the current system. * Gets the number of PCM modules in the current system.

View File

@@ -17,24 +17,6 @@ public class AnalogInDataJNI extends JNIWrapper {
public static native void setInitialized(int index, boolean initialized); public static native void setInitialized(int index, boolean initialized);
public static native int registerAverageBitsCallback(
int index, NotifyCallback callback, boolean initialNotify);
public static native void cancelAverageBitsCallback(int index, int uid);
public static native int getAverageBits(int index);
public static native void setAverageBits(int index, int averageBits);
public static native int registerOversampleBitsCallback(
int index, NotifyCallback callback, boolean initialNotify);
public static native void cancelOversampleBitsCallback(int index, int uid);
public static native int getOversampleBits(int index);
public static native void setOversampleBits(int index, int oversampleBits);
public static native int registerVoltageCallback( public static native int registerVoltageCallback(
int index, NotifyCallback callback, boolean initialNotify); int index, NotifyCallback callback, boolean initialNotify);

View File

@@ -86,95 +86,6 @@ Java_org_wpilib_hardware_hal_AnalogInputJNI_setAnalogInputSimDevice
(HAL_SimDeviceHandle)device); (HAL_SimDeviceHandle)device);
} }
/*
* Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: setAnalogSampleRate
* Signature: (D)V
*/
JNIEXPORT void JNICALL
Java_org_wpilib_hardware_hal_AnalogInputJNI_setAnalogSampleRate
(JNIEnv* env, jclass, jdouble value)
{
int32_t status = 0;
HAL_SetAnalogSampleRate(value, &status);
CheckStatus(env, status);
}
/*
* Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: getAnalogSampleRate
* Signature: ()D
*/
JNIEXPORT jdouble JNICALL
Java_org_wpilib_hardware_hal_AnalogInputJNI_getAnalogSampleRate
(JNIEnv* env, jclass)
{
int32_t status = 0;
double returnValue = HAL_GetAnalogSampleRate(&status);
CheckStatus(env, status);
return returnValue;
}
/*
* Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: setAnalogAverageBits
* Signature: (II)V
*/
JNIEXPORT void JNICALL
Java_org_wpilib_hardware_hal_AnalogInputJNI_setAnalogAverageBits
(JNIEnv* env, jclass, jint id, jint value)
{
int32_t status = 0;
HAL_SetAnalogAverageBits((HAL_AnalogInputHandle)id, value, &status);
CheckStatus(env, status);
}
/*
* Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: getAnalogAverageBits
* Signature: (I)I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_AnalogInputJNI_getAnalogAverageBits
(JNIEnv* env, jclass, jint id)
{
int32_t status = 0;
jint returnValue =
HAL_GetAnalogAverageBits((HAL_AnalogInputHandle)id, &status);
CheckStatus(env, status);
return returnValue;
}
/*
* Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: setAnalogOversampleBits
* Signature: (II)V
*/
JNIEXPORT void JNICALL
Java_org_wpilib_hardware_hal_AnalogInputJNI_setAnalogOversampleBits
(JNIEnv* env, jclass, jint id, jint value)
{
int32_t status = 0;
HAL_SetAnalogOversampleBits((HAL_AnalogInputHandle)id, value, &status);
CheckStatus(env, status);
}
/*
* Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: getAnalogOversampleBits
* Signature: (I)I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_AnalogInputJNI_getAnalogOversampleBits
(JNIEnv* env, jclass, jint id)
{
int32_t status = 0;
jint returnValue =
HAL_GetAnalogOversampleBits((HAL_AnalogInputHandle)id, &status);
CheckStatus(env, status);
return returnValue;
}
/* /*
* Class: org_wpilib_hardware_hal_AnalogInputJNI * Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: getAnalogValue * Method: getAnalogValue
@@ -190,22 +101,6 @@ Java_org_wpilib_hardware_hal_AnalogInputJNI_getAnalogValue
return returnValue; return returnValue;
} }
/*
* Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: getAnalogAverageValue
* Signature: (I)I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_AnalogInputJNI_getAnalogAverageValue
(JNIEnv* env, jclass, jint id)
{
int32_t status = 0;
jint returnValue =
HAL_GetAnalogAverageValue((HAL_AnalogInputHandle)id, &status);
CheckStatus(env, status);
return returnValue;
}
/* /*
* Class: org_wpilib_hardware_hal_AnalogInputJNI * Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: getAnalogVoltsToValue * Method: getAnalogVoltsToValue
@@ -254,52 +149,4 @@ Java_org_wpilib_hardware_hal_AnalogInputJNI_getAnalogVoltage
return returnValue; return returnValue;
} }
/*
* Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: getAnalogAverageVoltage
* Signature: (I)D
*/
JNIEXPORT jdouble JNICALL
Java_org_wpilib_hardware_hal_AnalogInputJNI_getAnalogAverageVoltage
(JNIEnv* env, jclass, jint id)
{
int32_t status = 0;
jdouble returnValue =
HAL_GetAnalogAverageVoltage((HAL_AnalogInputHandle)id, &status);
CheckStatus(env, status);
return returnValue;
}
/*
* Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: getAnalogLSBWeight
* Signature: (I)I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_AnalogInputJNI_getAnalogLSBWeight
(JNIEnv* env, jclass, jint id)
{
int32_t status = 0;
jint returnValue = HAL_GetAnalogLSBWeight((HAL_AnalogInputHandle)id, &status);
CheckStatus(env, status);
return returnValue;
}
/*
* Class: org_wpilib_hardware_hal_AnalogInputJNI
* Method: getAnalogOffset
* Signature: (I)I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_AnalogInputJNI_getAnalogOffset
(JNIEnv* env, jclass, jint id)
{
int32_t status = 0;
jint returnValue = HAL_GetAnalogOffset((HAL_AnalogInputHandle)id, &status);
CheckStatus(env, status);
return returnValue;
}
} // extern "C" } // extern "C"

View File

@@ -1,28 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include <jni.h>
#include <cassert>
#include "HALUtil.hpp"
#include "org_wpilib_hardware_hal_ConstantsJNI.h"
#include "wpi/hal/Constants.h"
using namespace wpi::hal;
extern "C" {
/*
* Class: org_wpilib_hardware_hal_ConstantsJNI
* Method: getSystemClockTicksPerMicrosecond
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_ConstantsJNI_getSystemClockTicksPerMicrosecond
(JNIEnv* env, jclass)
{
jint value = HAL_GetSystemClockTicksPerMicrosecond();
return value;
}
} // extern "C"

View File

@@ -24,10 +24,6 @@
using namespace wpi::util::java; using namespace wpi::util::java;
static_assert(org_wpilib_hardware_hal_HALUtil_RUNTIME_ROBORIO ==
HAL_RUNTIME_ROBORIO);
static_assert(org_wpilib_hardware_hal_HALUtil_RUNTIME_ROBORIO_2 ==
HAL_RUNTIME_ROBORIO_2);
static_assert(org_wpilib_hardware_hal_HALUtil_RUNTIME_SIMULATION == static_assert(org_wpilib_hardware_hal_HALUtil_RUNTIME_SIMULATION ==
HAL_RUNTIME_SIMULATION); HAL_RUNTIME_SIMULATION);
static_assert(org_wpilib_hardware_hal_HALUtil_RUNTIME_SYSTEMCORE == static_assert(org_wpilib_hardware_hal_HALUtil_RUNTIME_SYSTEMCORE ==

View File

@@ -28,92 +28,14 @@ Java_org_wpilib_hardware_hal_PortsJNI_getNumCanBuses
/* /*
* Class: org_wpilib_hardware_hal_PortsJNI * Class: org_wpilib_hardware_hal_PortsJNI
* Method: getNumAnalogInputs * Method: getNumSmartIo
* Signature: ()I * Signature: ()I
*/ */
JNIEXPORT jint JNICALL JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_PortsJNI_getNumAnalogInputs Java_org_wpilib_hardware_hal_PortsJNI_getNumSmartIo
(JNIEnv* env, jclass) (JNIEnv* env, jclass)
{ {
jint value = HAL_GetNumAnalogInputs(); jint value = HAL_GetNumSmartIo();
return value;
}
/*
* Class: org_wpilib_hardware_hal_PortsJNI
* Method: getNumCounters
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_PortsJNI_getNumCounters
(JNIEnv* env, jclass)
{
jint value = HAL_GetNumCounters();
return value;
}
/*
* Class: org_wpilib_hardware_hal_PortsJNI
* Method: getNumDigitalChannels
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_PortsJNI_getNumDigitalChannels
(JNIEnv* env, jclass)
{
jint value = HAL_GetNumDigitalChannels();
return value;
}
/*
* Class: org_wpilib_hardware_hal_PortsJNI
* Method: getNumPWMChannels
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_PortsJNI_getNumPWMChannels
(JNIEnv* env, jclass)
{
jint value = HAL_GetNumPWMChannels();
return value;
}
/*
* Class: org_wpilib_hardware_hal_PortsJNI
* Method: getNumDigitalPWMOutputs
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_PortsJNI_getNumDigitalPWMOutputs
(JNIEnv* env, jclass)
{
jint value = HAL_GetNumDigitalPWMOutputs();
return value;
}
/*
* Class: org_wpilib_hardware_hal_PortsJNI
* Method: getNumEncoders
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_PortsJNI_getNumEncoders
(JNIEnv* env, jclass)
{
jint value = HAL_GetNumEncoders();
return value;
}
/*
* Class: org_wpilib_hardware_hal_PortsJNI
* Method: getNumInterrupts
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_PortsJNI_getNumInterrupts
(JNIEnv* env, jclass)
{
jint value = HAL_GetNumInterrupts();
return value; return value;
} }

View File

@@ -62,106 +62,6 @@ Java_org_wpilib_hardware_hal_simulation_AnalogInDataJNI_setInitialized
HALSIM_SetAnalogInInitialized(index, value); HALSIM_SetAnalogInInitialized(index, value);
} }
/*
* Class: org_wpilib_hardware_hal_simulation_AnalogInDataJNI
* Method: registerAverageBitsCallback
* Signature: (ILjava/lang/Object;Z)I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_simulation_AnalogInDataJNI_registerAverageBitsCallback
(JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
{
return sim::AllocateCallback(env, index, callback, initialNotify,
&HALSIM_RegisterAnalogInAverageBitsCallback);
}
/*
* Class: org_wpilib_hardware_hal_simulation_AnalogInDataJNI
* Method: cancelAverageBitsCallback
* Signature: (II)V
*/
JNIEXPORT void JNICALL
Java_org_wpilib_hardware_hal_simulation_AnalogInDataJNI_cancelAverageBitsCallback
(JNIEnv* env, jclass, jint index, jint handle)
{
return sim::FreeCallback(env, handle, index,
&HALSIM_CancelAnalogInAverageBitsCallback);
}
/*
* Class: org_wpilib_hardware_hal_simulation_AnalogInDataJNI
* Method: getAverageBits
* Signature: (I)I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_simulation_AnalogInDataJNI_getAverageBits
(JNIEnv*, jclass, jint index)
{
return HALSIM_GetAnalogInAverageBits(index);
}
/*
* Class: org_wpilib_hardware_hal_simulation_AnalogInDataJNI
* Method: setAverageBits
* Signature: (II)V
*/
JNIEXPORT void JNICALL
Java_org_wpilib_hardware_hal_simulation_AnalogInDataJNI_setAverageBits
(JNIEnv*, jclass, jint index, jint value)
{
HALSIM_SetAnalogInAverageBits(index, value);
}
/*
* Class: org_wpilib_hardware_hal_simulation_AnalogInDataJNI
* Method: registerOversampleBitsCallback
* Signature: (ILjava/lang/Object;Z)I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_simulation_AnalogInDataJNI_registerOversampleBitsCallback
(JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
{
return sim::AllocateCallback(env, index, callback, initialNotify,
&HALSIM_RegisterAnalogInOversampleBitsCallback);
}
/*
* Class: org_wpilib_hardware_hal_simulation_AnalogInDataJNI
* Method: cancelOversampleBitsCallback
* Signature: (II)V
*/
JNIEXPORT void JNICALL
Java_org_wpilib_hardware_hal_simulation_AnalogInDataJNI_cancelOversampleBitsCallback
(JNIEnv* env, jclass, jint index, jint handle)
{
return sim::FreeCallback(env, handle, index,
&HALSIM_CancelAnalogInOversampleBitsCallback);
}
/*
* Class: org_wpilib_hardware_hal_simulation_AnalogInDataJNI
* Method: getOversampleBits
* Signature: (I)I
*/
JNIEXPORT jint JNICALL
Java_org_wpilib_hardware_hal_simulation_AnalogInDataJNI_getOversampleBits
(JNIEnv*, jclass, jint index)
{
return HALSIM_GetAnalogInOversampleBits(index);
}
/*
* Class: org_wpilib_hardware_hal_simulation_AnalogInDataJNI
* Method: setOversampleBits
* Signature: (II)V
*/
JNIEXPORT void JNICALL
Java_org_wpilib_hardware_hal_simulation_AnalogInDataJNI_setOversampleBits
(JNIEnv*, jclass, jint index, jint value)
{
HALSIM_SetAnalogInOversampleBits(index, value);
}
/* /*
* Class: org_wpilib_hardware_hal_simulation_AnalogInDataJNI * Class: org_wpilib_hardware_hal_simulation_AnalogInDataJNI
* Method: registerVoltageCallback * Method: registerVoltageCallback

View File

@@ -64,83 +64,6 @@ HAL_Bool HAL_CheckAnalogInputChannel(int32_t channel);
void HAL_SetAnalogInputSimDevice(HAL_AnalogInputHandle handle, void HAL_SetAnalogInputSimDevice(HAL_AnalogInputHandle handle,
HAL_SimDeviceHandle device); HAL_SimDeviceHandle device);
/**
* Sets the sample rate.
*
* This is a global setting for the Athena and effects all channels.
*
* @param[in] samplesPerSecond The number of samples per channel per second.
* @param[out] status the error code, or 0 for success
*/
void HAL_SetAnalogSampleRate(double samplesPerSecond, int32_t* status);
/**
* Gets the current sample rate.
*
* This assumes one entry in the scan list.
* This is a global setting for the Athena and effects all channels.
*
* @param[out] status the error code, or 0 for success
* @return Sample rate.
*/
double HAL_GetAnalogSampleRate(int32_t* status);
/**
* Sets the number of averaging bits.
*
* This sets the number of averaging bits. The actual number of averaged samples
* is 2**bits. Use averaging to improve the stability of your measurement at the
* expense of sampling rate. The averaging is done automatically in the FPGA.
*
* @param[in] analogPortHandle Handle to the analog port to configure.
* @param[in] bits Number of bits to average.
* @param[out] status the error code, or 0 for success
*/
void HAL_SetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
int32_t bits, int32_t* status);
/**
* Gets 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.
*
* @param[in] analogPortHandle Handle to the analog port to use.
* @param[out] status the error code, or 0 for success
* @return Bits to average.
*/
int32_t HAL_GetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
int32_t* status);
/**
* Sets the number of oversample bits.
*
* This sets the number of oversample bits. The actual number of oversampled
* values is 2**bits. Use oversampling to improve the resolution of your
* measurements at the expense of sampling rate. The oversampling is done
* automatically in the FPGA.
*
* @param[in] analogPortHandle Handle to the analog port to use.
* @param[in] bits Number of bits to oversample.
* @param[out] status the error code, or 0 for success
*/
void HAL_SetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
int32_t bits, int32_t* status);
/**
* Gets 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.
*
* @param[in] analogPortHandle Handle to the analog port to use.
* @param[out] status the error code, or 0 for success
* @return Bits to oversample.
*/
int32_t HAL_GetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
int32_t* status);
/** /**
* Gets a sample straight from the channel on this module. * Gets a sample straight from the channel on this module.
* *
@@ -155,24 +78,6 @@ int32_t HAL_GetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle, int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle,
int32_t* status); int32_t* status);
/**
* Gets a sample from the output of the oversample and average engine for the
* channel.
*
* The sample is 12-bit + the value 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 the module on this channel. Use GetAverageVoltage() to get the analog
* value in calibrated units.
*
* @param[in] analogPortHandle Handle to the analog port to use.
* @param[out] status the error code, or 0 for success
* @return A sample from the oversample and average engine for the channel.
*/
int32_t HAL_GetAnalogAverageValue(HAL_AnalogInputHandle analogPortHandle,
int32_t* status);
/** /**
* Converts a voltage to a raw value for a specified channel. * Converts a voltage to a raw value for a specified channel.
* *
@@ -192,8 +97,7 @@ int32_t HAL_GetAnalogVoltsToValue(HAL_AnalogInputHandle analogPortHandle,
/** /**
* Gets a scaled sample straight from the channel on this module. * Gets a scaled sample straight from the channel on this module.
* *
* The value is scaled to units of Volts using the calibrated scaling data from * The value is scaled to units of Volts.
* GetLSBWeight() and GetOffset().
* *
* @param[in] analogPortHandle Handle to the analog port to use. * @param[in] analogPortHandle Handle to the analog port to use.
* @param[out] status the error code, or 0 for success * @param[out] status the error code, or 0 for success
@@ -202,51 +106,6 @@ int32_t HAL_GetAnalogVoltsToValue(HAL_AnalogInputHandle analogPortHandle,
double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle, double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle,
int32_t* status); int32_t* status);
/**
* Gets a scaled sample from the output of the oversample and average engine for
* the 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.
*
* @param[in] analogPortHandle Handle to the analog port to use.
* @param[out] status the error code, or 0 for success
* @return A scaled sample from the output of the oversample and average engine
* for the channel.
*/
double HAL_GetAnalogAverageVoltage(HAL_AnalogInputHandle analogPortHandle,
int32_t* status);
/**
* Gets the factory scaling least significant bit weight constant.
* The least significant bit weight constant for the channel that was calibrated
* in manufacturing and stored in an eeprom in the module.
*
* Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
*
* @param[in] analogPortHandle Handle to the analog port to use.
* @param[out] status the error code, or 0 for success
* @return Least significant bit weight.
*/
int32_t HAL_GetAnalogLSBWeight(HAL_AnalogInputHandle analogPortHandle,
int32_t* status);
/**
* Gets the factory scaling offset constant.
* The offset constant for the channel that was calibrated in manufacturing and
* stored in an eeprom in the module.
*
* Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
*
* @param[in] analogPortHandle Handle to the analog port to use.
* @param[out] status Error status variable. 0 on success.
* @return Offset constant.
*/
int32_t HAL_GetAnalogOffset(HAL_AnalogInputHandle analogPortHandle,
int32_t* status);
/** /**
* Get the analog voltage from a raw value. * Get the analog voltage from a raw value.
* *

View File

@@ -1,28 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#pragma once
#include <stdint.h>
/**
* @defgroup hal_constants Constants Functions
* @ingroup hal_capi
* @{
*/
#ifdef __cplusplus
extern "C" {
#endif
/**
* Gets the number of FPGA system clock ticks per microsecond.
*
* @return the number of clock ticks per microsecond
*/
int32_t HAL_GetSystemClockTicksPerMicrosecond(void);
#ifdef __cplusplus
} // extern "C"
#endif
/** @} */

View File

@@ -25,14 +25,10 @@
* Runtime type. * Runtime type.
*/ */
HAL_ENUM(HAL_RuntimeType) { HAL_ENUM(HAL_RuntimeType) {
/** roboRIO 1.0 */ /** Systemcore runtime */
HAL_RUNTIME_ROBORIO,
/** roboRIO 2.0 */
HAL_RUNTIME_ROBORIO_2,
/** Simulation runtime */
HAL_RUNTIME_SIMULATION,
/** Systemcore */
HAL_RUNTIME_SYSTEMCORE, HAL_RUNTIME_SYSTEMCORE,
/** Simulation runtime */
HAL_RUNTIME_SIMULATION
}; };
#ifdef __cplusplus #ifdef __cplusplus

View File

@@ -23,6 +23,13 @@ extern "C" {
*/ */
int32_t HAL_GetNumCanBuses(void); int32_t HAL_GetNumCanBuses(void);
/**
* Gets the number of smart IO channels in the current system.
*
* @return the number of SmartIO
*/
int32_t HAL_GetNumSmartIo(void);
/** /**
* Gets the number of analog inputs in the current system. * Gets the number of analog inputs in the current system.
* *

View File

@@ -22,21 +22,6 @@ void HALSIM_SetAnalogInInitialized(int32_t index, HAL_Bool initialized);
HAL_SimDeviceHandle HALSIM_GetAnalogInSimDevice(int32_t index); HAL_SimDeviceHandle HALSIM_GetAnalogInSimDevice(int32_t index);
int32_t HALSIM_RegisterAnalogInAverageBitsCallback(int32_t index,
HAL_NotifyCallback callback,
void* param,
HAL_Bool initialNotify);
void HALSIM_CancelAnalogInAverageBitsCallback(int32_t index, int32_t uid);
int32_t HALSIM_GetAnalogInAverageBits(int32_t index);
void HALSIM_SetAnalogInAverageBits(int32_t index, int32_t averageBits);
int32_t HALSIM_RegisterAnalogInOversampleBitsCallback(
int32_t index, HAL_NotifyCallback callback, void* param,
HAL_Bool initialNotify);
void HALSIM_CancelAnalogInOversampleBitsCallback(int32_t index, int32_t uid);
int32_t HALSIM_GetAnalogInOversampleBits(int32_t index);
void HALSIM_SetAnalogInOversampleBits(int32_t index, int32_t oversampleBits);
int32_t HALSIM_RegisterAnalogInVoltageCallback(int32_t index, int32_t HALSIM_RegisterAnalogInVoltageCallback(int32_t index,
HAL_NotifyCallback callback, HAL_NotifyCallback callback,
void* param, void* param,

View File

@@ -18,13 +18,6 @@ extern "C" {
#endif #endif
void HALSIM_ResetRoboRioData(void); void HALSIM_ResetRoboRioData(void);
int32_t HALSIM_RegisterRoboRioFPGAButtonCallback(HAL_NotifyCallback callback,
void* param,
HAL_Bool initialNotify);
void HALSIM_CancelRoboRioFPGAButtonCallback(int32_t uid);
HAL_Bool HALSIM_GetRoboRioFPGAButton(void);
void HALSIM_SetRoboRioFPGAButton(HAL_Bool fPGAButton);
int32_t HALSIM_RegisterRoboRioVInVoltageCallback(HAL_NotifyCallback callback, int32_t HALSIM_RegisterRoboRioVInVoltageCallback(HAL_NotifyCallback callback,
void* param, void* param,
HAL_Bool initialNotify); HAL_Bool initialNotify);

View File

@@ -43,7 +43,6 @@ HAL_AnalogInputHandle HAL_InitializeAnalogInputPort(
} }
analog_port->channel = static_cast<uint8_t>(channel); analog_port->channel = static_cast<uint8_t>(channel);
analog_port->isAccumulator = false;
SimAnalogInData[channel].initialized = true; SimAnalogInData[channel].initialized = true;
SimAnalogInData[channel].simDevice = 0; SimAnalogInData[channel].simDevice = 0;
@@ -80,52 +79,6 @@ void HAL_SetAnalogInputSimDevice(HAL_AnalogInputHandle handle,
SimAnalogInData[port->channel].simDevice = device; SimAnalogInData[port->channel].simDevice = device;
} }
void HAL_SetAnalogSampleRate(double samplesPerSecond, int32_t* status) {
// No op
}
double HAL_GetAnalogSampleRate(int32_t* status) {
return kDefaultSampleRate;
}
void HAL_SetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
int32_t bits, int32_t* status) {
auto port = analogInputHandles->Get(analogPortHandle);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
SimAnalogInData[port->channel].averageBits = bits;
}
int32_t HAL_GetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
auto port = analogInputHandles->Get(analogPortHandle);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return 0;
}
return SimAnalogInData[port->channel].averageBits;
}
void HAL_SetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
int32_t bits, int32_t* status) {
auto port = analogInputHandles->Get(analogPortHandle);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
SimAnalogInData[port->channel].oversampleBits = bits;
}
int32_t HAL_GetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
auto port = analogInputHandles->Get(analogPortHandle);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return 0;
}
return SimAnalogInData[port->channel].oversampleBits;
}
int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle, int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) { int32_t* status) {
auto port = analogInputHandles->Get(analogPortHandle); auto port = analogInputHandles->Get(analogPortHandle);
@@ -137,27 +90,12 @@ int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle,
double voltage = SimAnalogInData[port->channel].voltage; double voltage = SimAnalogInData[port->channel].voltage;
return HAL_GetAnalogVoltsToValue(analogPortHandle, voltage, status); return HAL_GetAnalogVoltsToValue(analogPortHandle, voltage, status);
} }
int32_t HAL_GetAnalogAverageValue(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
// No averaging supported
return HAL_GetAnalogValue(analogPortHandle, status);
}
int32_t HAL_GetAnalogVoltsToValue(HAL_AnalogInputHandle analogPortHandle, int32_t HAL_GetAnalogVoltsToValue(HAL_AnalogInputHandle analogPortHandle,
double voltage, int32_t* status) { double voltage, int32_t* status) {
if (voltage > 5.0) { return static_cast<int32_t>(voltage * 4095.0 / 3.3);
voltage = 5.0;
*status = VOLTAGE_OUT_OF_RANGE;
}
if (voltage < 0.0) {
voltage = 0.0;
*status = VOLTAGE_OUT_OF_RANGE;
}
int32_t LSBWeight = HAL_GetAnalogLSBWeight(analogPortHandle, status);
int32_t offset = HAL_GetAnalogOffset(analogPortHandle, status);
int32_t value =
static_cast<int32_t>((voltage + offset * 1.0e-9) / (LSBWeight * 1.0e-9));
return value;
} }
double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle, double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) { int32_t* status) {
auto port = analogInputHandles->Get(analogPortHandle); auto port = analogInputHandles->Get(analogPortHandle);
@@ -171,29 +109,6 @@ double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle,
double HAL_GetAnalogValueToVolts(HAL_AnalogInputHandle analogPortHandle, double HAL_GetAnalogValueToVolts(HAL_AnalogInputHandle analogPortHandle,
int32_t rawValue, int32_t* status) { int32_t rawValue, int32_t* status) {
int32_t LSBWeight = HAL_GetAnalogLSBWeight(analogPortHandle, status); return rawValue / 4095.0 * 3.3;
int32_t offset = HAL_GetAnalogOffset(analogPortHandle, status);
double voltage = LSBWeight * 1.0e-9 * rawValue - offset * 1.0e-9;
return voltage;
}
double HAL_GetAnalogAverageVoltage(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
auto port = analogInputHandles->Get(analogPortHandle);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return 0.0;
}
// No averaging supported
return SimAnalogInData[port->channel].voltage;
}
int32_t HAL_GetAnalogLSBWeight(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
return 1220703;
}
int32_t HAL_GetAnalogOffset(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
return 0;
} }
} // extern "C" } // extern "C"

View File

@@ -13,15 +13,9 @@
#include "wpi/hal/handles/IndexedHandleResource.hpp" #include "wpi/hal/handles/IndexedHandleResource.hpp"
namespace wpi::hal { namespace wpi::hal {
constexpr int32_t kTimebase = 40000000; ///< 40 MHz clock
constexpr int32_t kDefaultOversampleBits = 0;
constexpr int32_t kDefaultAverageBits = 7;
constexpr double kDefaultSampleRate = 50000.0;
static constexpr uint32_t kAccumulatorChannels[] = {0, 1};
struct AnalogPort { struct AnalogPort {
uint8_t channel; uint8_t channel;
bool isAccumulator;
std::string previousAllocation; std::string previousAllocation;
}; };

View File

@@ -1,19 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "wpi/hal/Constants.h"
#include "ConstantsInternal.hpp"
using namespace wpi::hal;
namespace wpi::hal::init {
void InitializeConstants() {}
} // namespace wpi::hal::init
extern "C" {
int32_t HAL_GetSystemClockTicksPerMicrosecond(void) {
return kSystemClockTicksPerMicrosecond;
}
} // extern "C"

View File

@@ -1,11 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#pragma once
#include <stdint.h>
namespace wpi::hal {
constexpr int32_t kSystemClockTicksPerMicrosecond = 40;
} // namespace wpi::hal

View File

@@ -86,7 +86,6 @@ void InitializeHAL() {
InitializeAnalogInput(); InitializeAnalogInput();
InitializeAnalogInternal(); InitializeAnalogInternal();
InitializeCAN(); InitializeCAN();
InitializeConstants();
InitializeCounter(); InitializeCounter();
InitializeDigitalInternal(); InitializeDigitalInternal();
InitializeDIO(); InitializeDIO();

View File

@@ -38,7 +38,6 @@ extern void InitializeAlert();
extern void InitializeAnalogInput(); extern void InitializeAnalogInput();
extern void InitializeAnalogInternal(); extern void InitializeAnalogInternal();
extern void InitializeCAN(); extern void InitializeCAN();
extern void InitializeConstants();
extern void InitializeCounter(); extern void InitializeCounter();
extern void InitializeDigitalInternal(); extern void InitializeDigitalInternal();
extern void InitializeDIO(); extern void InitializeDIO();

View File

@@ -7,7 +7,6 @@
#include <algorithm> #include <algorithm>
#include <atomic> #include <atomic>
#include <chrono> #include <chrono>
#include <cstdio>
#include <thread> #include <thread>
#include "MockHooksInternal.hpp" #include "MockHooksInternal.hpp"

View File

@@ -4,8 +4,6 @@
#include "wpi/hal/PWM.h" #include "wpi/hal/PWM.h"
#include <cmath>
#include "DigitalInternal.hpp" #include "DigitalInternal.hpp"
#include "HALInitializer.hpp" #include "HALInitializer.hpp"
#include "HALInternal.hpp" #include "HALInternal.hpp"

View File

@@ -16,6 +16,9 @@ extern "C" {
int32_t HAL_GetNumCanBuses(void) { int32_t HAL_GetNumCanBuses(void) {
return kNumCanBuses; return kNumCanBuses;
} }
int32_t HAL_GetNumSmartIo(void) {
return kNumSmartIo;
}
int32_t HAL_GetNumAnalogInputs(void) { int32_t HAL_GetNumAnalogInputs(void) {
return kNumAnalogInputs; return kNumAnalogInputs;
} }

View File

@@ -9,6 +9,7 @@
namespace wpi::hal { namespace wpi::hal {
constexpr int32_t kNumCanBuses = 5; constexpr int32_t kNumCanBuses = 5;
constexpr int32_t kAccelerometers = 1; constexpr int32_t kAccelerometers = 1;
constexpr int32_t kNumSmartIo = 6;
constexpr int32_t kNumAccumulators = 2; constexpr int32_t kNumAccumulators = 2;
constexpr int32_t kNumAnalogInputs = 8; constexpr int32_t kNumAnalogInputs = 8;
constexpr int32_t kNumAnalogOutputs = 2; constexpr int32_t kNumAnalogOutputs = 2;

View File

@@ -18,8 +18,6 @@ AnalogInData* wpi::hal::SimAnalogInData;
void AnalogInData::ResetData() { void AnalogInData::ResetData() {
initialized.Reset(false); initialized.Reset(false);
simDevice = 0; simDevice = 0;
averageBits.Reset(7);
oversampleBits.Reset(0);
voltage.Reset(0.0); voltage.Reset(0.0);
} }
@@ -37,8 +35,6 @@ HAL_SimDeviceHandle HALSIM_GetAnalogInSimDevice(int32_t index) {
SimAnalogInData, LOWERNAME) SimAnalogInData, LOWERNAME)
DEFINE_CAPI(HAL_Bool, Initialized, initialized) DEFINE_CAPI(HAL_Bool, Initialized, initialized)
DEFINE_CAPI(int32_t, AverageBits, averageBits)
DEFINE_CAPI(int32_t, OversampleBits, oversampleBits)
DEFINE_CAPI(double, Voltage, voltage) DEFINE_CAPI(double, Voltage, voltage)
#define REGISTER(NAME) \ #define REGISTER(NAME) \
@@ -48,8 +44,6 @@ void HALSIM_RegisterAnalogInAllCallbacks(int32_t index,
HAL_NotifyCallback callback, HAL_NotifyCallback callback,
void* param, HAL_Bool initialNotify) { void* param, HAL_Bool initialNotify) {
REGISTER(initialized); REGISTER(initialized);
REGISTER(averageBits);
REGISTER(oversampleBits);
REGISTER(voltage); REGISTER(voltage);
} }
} // extern "C" } // extern "C"

View File

@@ -11,16 +11,12 @@
namespace wpi::hal { namespace wpi::hal {
class AnalogInData { class AnalogInData {
HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
HAL_SIMDATAVALUE_DEFINE_NAME(AverageBits)
HAL_SIMDATAVALUE_DEFINE_NAME(OversampleBits)
HAL_SIMDATAVALUE_DEFINE_NAME(Voltage) HAL_SIMDATAVALUE_DEFINE_NAME(Voltage)
public: public:
SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{ SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
false}; false};
std::atomic<HAL_SimDeviceHandle> simDevice; std::atomic<HAL_SimDeviceHandle> simDevice;
SimDataValue<int32_t, HAL_MakeInt, GetAverageBitsName> averageBits{7};
SimDataValue<int32_t, HAL_MakeInt, GetOversampleBitsName> oversampleBits{0};
SimDataValue<double, HAL_MakeDouble, GetVoltageName> voltage{0.0}; SimDataValue<double, HAL_MakeDouble, GetVoltageName> voltage{0.0};
virtual void ResetData(); virtual void ResetData();

View File

@@ -96,40 +96,6 @@ HAL_Bool HAL_CheckAnalogInputChannel(int32_t channel) {
void HAL_SetAnalogInputSimDevice(HAL_AnalogInputHandle handle, void HAL_SetAnalogInputSimDevice(HAL_AnalogInputHandle handle,
HAL_SimDeviceHandle device) {} HAL_SimDeviceHandle device) {}
void HAL_SetAnalogSampleRate(double samplesPerSecond, int32_t* status) {
*status = HAL_HANDLE_ERROR;
return;
}
double HAL_GetAnalogSampleRate(int32_t* status) {
*status = HAL_HANDLE_ERROR;
return 0;
}
void HAL_SetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
int32_t bits, int32_t* status) {
*status = HAL_HANDLE_ERROR;
return;
}
int32_t HAL_GetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
*status = HAL_HANDLE_ERROR;
return 0;
}
void HAL_SetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
int32_t bits, int32_t* status) {
*status = HAL_HANDLE_ERROR;
return;
}
int32_t HAL_GetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
*status = HAL_HANDLE_ERROR;
return 0;
}
int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle, int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) { int32_t* status) {
auto port = auto port =
@@ -144,16 +110,9 @@ int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle,
return ret; return ret;
} }
int32_t HAL_GetAnalogAverageValue(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
*status = HAL_HANDLE_ERROR;
return 0;
}
int32_t HAL_GetAnalogVoltsToValue(HAL_AnalogInputHandle analogPortHandle, int32_t HAL_GetAnalogVoltsToValue(HAL_AnalogInputHandle analogPortHandle,
double voltage, int32_t* status) { double voltage, int32_t* status) {
*status = HAL_HANDLE_ERROR; return static_cast<int32_t>(voltage * 4095.0 / 3.3);
return 0;
} }
double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle, double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle,
@@ -173,26 +132,7 @@ double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle,
double HAL_GetAnalogValueToVolts(HAL_AnalogInputHandle analogPortHandle, double HAL_GetAnalogValueToVolts(HAL_AnalogInputHandle analogPortHandle,
int32_t rawValue, int32_t* status) { int32_t rawValue, int32_t* status) {
*status = HAL_HANDLE_ERROR; return rawValue / 4095.0 * 3.3;
return 0;
}
double HAL_GetAnalogAverageVoltage(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
*status = HAL_HANDLE_ERROR;
return 0;
}
int32_t HAL_GetAnalogLSBWeight(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
*status = HAL_HANDLE_ERROR;
return 0;
}
int32_t HAL_GetAnalogOffset(HAL_AnalogInputHandle analogPortHandle,
int32_t* status) {
*status = HAL_HANDLE_ERROR;
return 0;
} }
} // extern "C" } // extern "C"

View File

@@ -1,19 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "wpi/hal/Constants.h"
#include "ConstantsInternal.hpp"
using namespace wpi::hal;
namespace wpi::hal::init {
void InitializeConstants() {}
} // namespace wpi::hal::init
extern "C" {
int32_t HAL_GetSystemClockTicksPerMicrosecond(void) {
return kSystemClockTicksPerMicrosecond;
}
} // extern "C"

View File

@@ -1,11 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#pragma once
#include <stdint.h>
namespace wpi::hal {
constexpr int32_t kSystemClockTicksPerMicrosecond = 40;
} // namespace wpi::hal

View File

@@ -42,7 +42,6 @@ void InitializeHAL() {
InitializeAnalogInput(); InitializeAnalogInput();
InitializeCAN(); InitializeCAN();
InitializeCANAPI(); InitializeCANAPI();
InitializeConstants();
InitializeCounter(); InitializeCounter();
InitializeDIO(); InitializeDIO();
InitializeDutyCycle(); InitializeDutyCycle();

View File

@@ -23,7 +23,6 @@ extern void InitializeAnalogInput();
extern void InitializeAnalogInternal(); extern void InitializeAnalogInternal();
extern void InitializeCAN(); extern void InitializeCAN();
extern void InitializeCANAPI(); extern void InitializeCANAPI();
extern void InitializeConstants();
extern void InitializeCounter(); extern void InitializeCounter();
extern void InitializeDigitalInternal(); extern void InitializeDigitalInternal();
extern void InitializeDIO(); extern void InitializeDIO();

View File

@@ -16,6 +16,9 @@ extern "C" {
int32_t HAL_GetNumCanBuses(void) { int32_t HAL_GetNumCanBuses(void) {
return kNumCanBuses; return kNumCanBuses;
} }
int32_t HAL_GetNumSmartIo(void) {
return kNumSmartIo;
}
int32_t HAL_GetNumAnalogInputs(void) { int32_t HAL_GetNumAnalogInputs(void) {
return kNumAnalogInputs; return kNumAnalogInputs;
} }

View File

@@ -17,8 +17,6 @@ HAL_SimDeviceHandle HALSIM_GetAnalogInSimDevice(int32_t index) {
HAL_SIMDATAVALUE_STUB_CAPI(TYPE, HALSIM, AnalogIn##CAPINAME, RETURN) HAL_SIMDATAVALUE_STUB_CAPI(TYPE, HALSIM, AnalogIn##CAPINAME, RETURN)
DEFINE_CAPI(HAL_Bool, Initialized, false) DEFINE_CAPI(HAL_Bool, Initialized, false)
DEFINE_CAPI(int32_t, AverageBits, 0)
DEFINE_CAPI(int32_t, OversampleBits, 0)
DEFINE_CAPI(double, Voltage, 0) DEFINE_CAPI(double, Voltage, 0)
void HALSIM_RegisterAnalogInAllCallbacks(int32_t index, void HALSIM_RegisterAnalogInAllCallbacks(int32_t index,

View File

@@ -173,20 +173,6 @@ inline void RemoveRefreshedDataEventHandle(WPI_EventHandle event) {}
} // namespace DriverStation } // namespace DriverStation
// #ifdef __FIRST_SYSTEMCORE__
// static constexpr int ROBORIO = 0;
// namespace RobotBase {
// inline int GetRuntimeType() {
// nLoadOut::tTargetClass targetClass = nLoadOut::getTargetClass();
// if (targetClass == nLoadOut::kTargetClass_RoboRIO2) {
// return 1;
// } else {
// return 0;
// }
// }
// } // namespace RobotBase
// #endif
struct Thread final : public ::wpi::util::SafeThread { struct Thread final : public ::wpi::util::SafeThread {
Thread(std::string_view dir, std::string_view filename, double period); Thread(std::string_view dir, std::string_view filename, double period);
~Thread() override; ~Thread() override;

View File

@@ -111,8 +111,6 @@ The basic analog input just reads a voltage. An analog input can also be configu
| Data Key | Type | Description | | Data Key | Type | Description |
| ---------------------- | ------- | --------------------------------------------------- | | ---------------------- | ------- | --------------------------------------------------- |
| ``"<init"`` | Boolean | If analog input is initialized in the robot program | | ``"<init"`` | Boolean | If analog input is initialized in the robot program |
| ``"<avg_bits"`` | Integer | The number of averaging bits |
| ``"<oversample_bits"`` | Integer | The number of oversampling bits |
| ``">voltage"`` | Float | Input voltage, in volts | | ``">voltage"`` | Float | Input voltage, in volts |
#### Digital Input/Output ("DIO") #### Digital Input/Output ("DIO")

View File

@@ -127,12 +127,6 @@ components:
<init: <init:
type: boolean type: boolean
description: "If analog input is initialized in the robot program" description: "If analog input is initialized in the robot program"
"<avg_bits":
type: integer
description: "The number of averaging bits"
"<oversample_bits":
type: integer
description: "The number of oversampling bits"
">voltage": ">voltage":
type: number type: number
description: "Input voltage, in volts" description: "Input voltage, in volts"

View File

@@ -30,9 +30,6 @@ HALSimWSProviderAnalogIn::~HALSimWSProviderAnalogIn() {
void HALSimWSProviderAnalogIn::RegisterCallbacks() { void HALSimWSProviderAnalogIn::RegisterCallbacks() {
m_initCbKey = REGISTER_AIN(Initialized, "<init", bool, boolean); m_initCbKey = REGISTER_AIN(Initialized, "<init", bool, boolean);
m_avgbitsCbKey = REGISTER_AIN(AverageBits, "<avg_bits", int32_t, int);
m_oversampleCbKey =
REGISTER_AIN(OversampleBits, "<oversample_bits", int32_t, int);
m_voltageCbKey = REGISTER_AIN(Voltage, ">voltage", double, double); m_voltageCbKey = REGISTER_AIN(Voltage, ">voltage", double, double);
} }
@@ -43,14 +40,10 @@ void HALSimWSProviderAnalogIn::CancelCallbacks() {
void HALSimWSProviderAnalogIn::DoCancelCallbacks() { void HALSimWSProviderAnalogIn::DoCancelCallbacks() {
// Cancel callbacks // Cancel callbacks
HALSIM_CancelAnalogInInitializedCallback(m_channel, m_initCbKey); HALSIM_CancelAnalogInInitializedCallback(m_channel, m_initCbKey);
HALSIM_CancelAnalogInAverageBitsCallback(m_channel, m_avgbitsCbKey);
HALSIM_CancelAnalogInOversampleBitsCallback(m_channel, m_oversampleCbKey);
HALSIM_CancelAnalogInVoltageCallback(m_channel, m_voltageCbKey); HALSIM_CancelAnalogInVoltageCallback(m_channel, m_voltageCbKey);
// Reset callback IDs // Reset callback IDs
m_initCbKey = 0; m_initCbKey = 0;
m_avgbitsCbKey = 0;
m_oversampleCbKey = 0;
m_voltageCbKey = 0; m_voltageCbKey = 0;
} }

View File

@@ -26,8 +26,6 @@ class HALSimWSProviderAnalogIn : public HALSimWSHalChanProvider {
private: private:
int32_t m_initCbKey = 0; int32_t m_initCbKey = 0;
int32_t m_avgbitsCbKey = 0;
int32_t m_oversampleCbKey = 0;
int32_t m_voltageCbKey = 0; int32_t m_voltageCbKey = 0;
}; };

View File

@@ -17,10 +17,6 @@
using namespace wpi; using namespace wpi;
AnalogInput::AnalogInput(int channel) { AnalogInput::AnalogInput(int channel) {
if (!SensorUtil::CheckAnalogInputChannel(channel)) {
throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel);
}
m_channel = channel; m_channel = channel;
int32_t status = 0; int32_t status = 0;
std::string stackTrace = wpi::util::GetStackTrace(1); std::string stackTrace = wpi::util::GetStackTrace(1);
@@ -39,13 +35,6 @@ int AnalogInput::GetValue() const {
return value; return value;
} }
int AnalogInput::GetAverageValue() const {
int32_t status = 0;
int value = HAL_GetAnalogAverageValue(m_port, &status);
WPILIB_CheckErrorStatus(status, "Channel {}", m_channel);
return value;
}
double AnalogInput::GetVoltage() const { double AnalogInput::GetVoltage() const {
int32_t status = 0; int32_t status = 0;
double voltage = HAL_GetAnalogVoltage(m_port, &status); double voltage = HAL_GetAnalogVoltage(m_port, &status);
@@ -53,70 +42,10 @@ double AnalogInput::GetVoltage() const {
return voltage; return voltage;
} }
double AnalogInput::GetAverageVoltage() const {
int32_t status = 0;
double voltage = HAL_GetAnalogAverageVoltage(m_port, &status);
WPILIB_CheckErrorStatus(status, "Channel {}", m_channel);
return voltage;
}
int AnalogInput::GetChannel() const { int AnalogInput::GetChannel() const {
return m_channel; return m_channel;
} }
void AnalogInput::SetAverageBits(int bits) {
int32_t status = 0;
HAL_SetAnalogAverageBits(m_port, bits, &status);
WPILIB_CheckErrorStatus(status, "Channel {}", m_channel);
}
int AnalogInput::GetAverageBits() const {
int32_t status = 0;
int averageBits = HAL_GetAnalogAverageBits(m_port, &status);
WPILIB_CheckErrorStatus(status, "Channel {}", m_channel);
return averageBits;
}
void AnalogInput::SetOversampleBits(int bits) {
int32_t status = 0;
HAL_SetAnalogOversampleBits(m_port, bits, &status);
WPILIB_CheckErrorStatus(status, "Channel {}", m_channel);
}
int AnalogInput::GetOversampleBits() const {
int32_t status = 0;
int oversampleBits = HAL_GetAnalogOversampleBits(m_port, &status);
WPILIB_CheckErrorStatus(status, "Channel {}", m_channel);
return oversampleBits;
}
int AnalogInput::GetLSBWeight() const {
int32_t status = 0;
int lsbWeight = HAL_GetAnalogLSBWeight(m_port, &status);
WPILIB_CheckErrorStatus(status, "Channel {}", m_channel);
return lsbWeight;
}
int AnalogInput::GetOffset() const {
int32_t status = 0;
int offset = HAL_GetAnalogOffset(m_port, &status);
WPILIB_CheckErrorStatus(status, "Channel {}", m_channel);
return offset;
}
void AnalogInput::SetSampleRate(double samplesPerSecond) {
int32_t status = 0;
HAL_SetAnalogSampleRate(samplesPerSecond, &status);
WPILIB_CheckErrorStatus(status, "SetSampleRate");
}
double AnalogInput::GetSampleRate() {
int32_t status = 0;
double sampleRate = HAL_GetAnalogSampleRate(&status);
WPILIB_CheckErrorStatus(status, "GetSampleRate");
return sampleRate;
}
void AnalogInput::SetSimDevice(HAL_SimDeviceHandle device) { void AnalogInput::SetSimDevice(HAL_SimDeviceHandle device) {
HAL_SetAnalogInputSimDevice(m_port, device); HAL_SetAnalogInputSimDevice(m_port, device);
} }
@@ -124,5 +53,5 @@ void AnalogInput::SetSimDevice(HAL_SimDeviceHandle device) {
void AnalogInput::InitSendable(wpi::util::SendableBuilder& builder) { void AnalogInput::InitSendable(wpi::util::SendableBuilder& builder) {
builder.SetSmartDashboardType("Analog Input"); builder.SetSmartDashboardType("Analog Input");
builder.AddDoubleProperty( builder.AddDoubleProperty(
"Value", [=, this] { return GetAverageVoltage(); }, nullptr); "Value", [=, this] { return GetVoltage(); }, nullptr);
} }

View File

@@ -17,9 +17,6 @@
using namespace wpi; using namespace wpi;
DigitalInput::DigitalInput(int channel) { DigitalInput::DigitalInput(int channel) {
if (!SensorUtil::CheckDigitalChannel(channel)) {
throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel);
}
m_channel = channel; m_channel = channel;
int32_t status = 0; int32_t status = 0;

View File

@@ -18,9 +18,6 @@ using namespace wpi;
DigitalOutput::DigitalOutput(int channel) { DigitalOutput::DigitalOutput(int channel) {
m_pwmGenerator = HAL_INVALID_HANDLE; m_pwmGenerator = HAL_INVALID_HANDLE;
if (!SensorUtil::CheckDigitalChannel(channel)) {
throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel);
}
m_channel = channel; m_channel = channel;
int32_t status = 0; int32_t status = 0;
@@ -120,9 +117,6 @@ void DigitalOutput::DisablePWM() {
int32_t status = 0; int32_t status = 0;
// Disable the output by routing to a dead bit.
HAL_SetDigitalPWMOutputChannel(m_pwmGenerator,
SensorUtil::GetNumDigitalChannels(), &status);
WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); WPILIB_CheckErrorStatus(status, "Channel {}", m_channel);
HAL_FreeDigitalPWM(m_pwmGenerator); HAL_FreeDigitalPWM(m_pwmGenerator);

View File

@@ -15,10 +15,6 @@
using namespace wpi; using namespace wpi;
PWM::PWM(int channel, bool registerSendable) { PWM::PWM(int channel, bool registerSendable) {
if (!SensorUtil::CheckPWMChannel(channel)) {
throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel);
}
auto stack = wpi::util::GetStackTrace(1); auto stack = wpi::util::GetStackTrace(1);
int32_t status = 0; int32_t status = 0;
m_handle = HAL_InitializePWMPort(channel, stack.c_str(), &status); m_handle = HAL_InitializePWMPort(channel, stack.c_str(), &status);

View File

@@ -9,16 +9,11 @@
#include "wpi/hal/AddressableLED.h" #include "wpi/hal/AddressableLED.h"
#include "wpi/hal/UsageReporting.hpp" #include "wpi/hal/UsageReporting.hpp"
#include "wpi/system/Errors.hpp" #include "wpi/system/Errors.hpp"
#include "wpi/util/SensorUtil.hpp"
#include "wpi/util/StackTrace.hpp" #include "wpi/util/StackTrace.hpp"
using namespace wpi; using namespace wpi;
AddressableLED::AddressableLED(int channel) : m_channel{channel} { AddressableLED::AddressableLED(int channel) : m_channel{channel} {
if (!SensorUtil::CheckDigitalChannel(channel)) {
throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel);
}
int32_t status = 0; int32_t status = 0;
auto stack = wpi::util::GetStackTrace(1); auto stack = wpi::util::GetStackTrace(1);
m_handle = HAL_InitializeAddressableLED(channel, stack.c_str(), &status); m_handle = HAL_InitializeAddressableLED(channel, stack.c_str(), &status);

View File

@@ -16,9 +16,6 @@
using namespace wpi; using namespace wpi;
DutyCycle::DutyCycle(int channel) : m_channel{channel} { DutyCycle::DutyCycle(int channel) : m_channel{channel} {
if (!SensorUtil::CheckDigitalChannel(channel)) {
throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel);
}
InitDutyCycle(); InitDutyCycle();
} }

View File

@@ -34,40 +34,6 @@ void AnalogInputSim::SetInitialized(bool initialized) {
HALSIM_SetAnalogInInitialized(m_index, initialized); HALSIM_SetAnalogInInitialized(m_index, initialized);
} }
std::unique_ptr<CallbackStore> AnalogInputSim::RegisterAverageBitsCallback(
NotifyCallback callback, bool initialNotify) {
auto store = std::make_unique<CallbackStore>(
m_index, -1, callback, &HALSIM_CancelAnalogInAverageBitsCallback);
store->SetUid(HALSIM_RegisterAnalogInAverageBitsCallback(
m_index, &CallbackStoreThunk, store.get(), initialNotify));
return store;
}
int AnalogInputSim::GetAverageBits() const {
return HALSIM_GetAnalogInAverageBits(m_index);
}
void AnalogInputSim::SetAverageBits(int averageBits) {
HALSIM_SetAnalogInAverageBits(m_index, averageBits);
}
std::unique_ptr<CallbackStore> AnalogInputSim::RegisterOversampleBitsCallback(
NotifyCallback callback, bool initialNotify) {
auto store = std::make_unique<CallbackStore>(
m_index, -1, callback, &HALSIM_CancelAnalogInOversampleBitsCallback);
store->SetUid(HALSIM_RegisterAnalogInOversampleBitsCallback(
m_index, &CallbackStoreThunk, store.get(), initialNotify));
return store;
}
int AnalogInputSim::GetOversampleBits() const {
return HALSIM_GetAnalogInOversampleBits(m_index);
}
void AnalogInputSim::SetOversampleBits(int oversampleBits) {
HALSIM_SetAnalogInOversampleBits(m_index, oversampleBits);
}
std::unique_ptr<CallbackStore> AnalogInputSim::RegisterVoltageCallback( std::unique_ptr<CallbackStore> AnalogInputSim::RegisterVoltageCallback(
NotifyCallback callback, bool initialNotify) { NotifyCallback callback, bool initialNotify) {
auto store = std::make_unique<CallbackStore>( auto store = std::make_unique<CallbackStore>(

View File

@@ -4,9 +4,6 @@
#include "wpi/util/SensorUtil.hpp" #include "wpi/util/SensorUtil.hpp"
#include "wpi/hal/AnalogInput.h"
#include "wpi/hal/DIO.h"
#include "wpi/hal/PWM.h"
#include "wpi/hal/Ports.h" #include "wpi/hal/Ports.h"
using namespace wpi; using namespace wpi;
@@ -19,26 +16,6 @@ int SensorUtil::GetDefaultREVPHModule() {
return 1; return 1;
} }
bool SensorUtil::CheckDigitalChannel(int channel) { int SensorUtil::GetNumSmartIoPorts() {
return HAL_CheckDIOChannel(channel); return HAL_GetNumSmartIo();
}
bool SensorUtil::CheckPWMChannel(int channel) {
return HAL_CheckPWMChannel(channel);
}
bool SensorUtil::CheckAnalogInputChannel(int channel) {
return HAL_CheckAnalogInputChannel(channel);
}
int SensorUtil::GetNumDigitalChannels() {
return HAL_GetNumDigitalChannels();
}
int SensorUtil::GetNumAnalogInputs() {
return HAL_GetNumAnalogInputs();
}
int SensorUtil::GetNumPwmChannels() {
return HAL_GetNumPWMChannels();
} }

View File

@@ -28,14 +28,10 @@
#include "wpi/util/print.hpp" #include "wpi/util/print.hpp"
#include "wpi/util/timestamp.hpp" #include "wpi/util/timestamp.hpp"
static_assert(wpi::RuntimeType::ROBORIO ==
static_cast<wpi::RuntimeType>(HAL_RUNTIME_ROBORIO));
static_assert(wpi::RuntimeType::ROBORIO_2 ==
static_cast<wpi::RuntimeType>(HAL_RUNTIME_ROBORIO_2));
static_assert(wpi::RuntimeType::SIMULATION ==
static_cast<wpi::RuntimeType>(HAL_RUNTIME_SIMULATION));
static_assert(wpi::RuntimeType::SYSTEMCORE == static_assert(wpi::RuntimeType::SYSTEMCORE ==
static_cast<wpi::RuntimeType>(HAL_RUNTIME_SYSTEMCORE)); static_cast<wpi::RuntimeType>(HAL_RUNTIME_SYSTEMCORE));
static_assert(wpi::RuntimeType::SIMULATION ==
static_cast<wpi::RuntimeType>(HAL_RUNTIME_SIMULATION));
using SetCameraServerSharedFP = void (*)(wpi::CameraServerShared*); using SetCameraServerSharedFP = void (*)(wpi::CameraServerShared*);

View File

@@ -51,52 +51,15 @@ class AnalogInput : public wpi::util::Sendable,
*/ */
int GetValue() const; int GetValue() const;
/**
* 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 the
* module on this channel.
*
* Use GetAverageVoltage() to get the analog value in calibrated units.
*
* @return A sample from the oversample and average engine for this channel.
*/
int GetAverageValue() const;
/** /**
* Get a scaled sample straight from this channel. * Get a scaled sample straight from this channel.
* *
* The value is scaled to units of Volts using the calibrated scaling data * The value is scaled to units of Volts.
* from GetLSBWeight() and GetOffset().
* *
* @return A scaled sample straight from this channel. * @return A scaled sample straight from this channel.
*/ */
double GetVoltage() const; double GetVoltage() const;
/**
* 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.
*/
double GetAverageVoltage() const;
/** /**
* Get the channel number. * Get the channel number.
* *
@@ -104,88 +67,6 @@ class AnalogInput : public wpi::util::Sendable,
*/ */
int GetChannel() const; int GetChannel() const;
/**
* Set the number of averaging bits.
*
* This sets the number of averaging bits. The actual number of averaged
* samples is 2^bits.
*
* Use averaging to improve the stability of your measurement at the expense
* of sampling rate. The averaging is done automatically in the FPGA.
*
* @param bits Number of bits of averaging.
*/
void SetAverageBits(int bits);
/**
* Get the number of averaging bits previously configured.
*
* 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 Number of bits of averaging previously configured.
*/
int GetAverageBits() const;
/**
* Set the number of oversample bits.
*
* This sets the number of oversample bits. The actual number of oversampled
* values is 2^bits. Use oversampling to improve the resolution of your
* measurements at the expense of sampling rate. The oversampling is done
* automatically in the FPGA.
*
* @param bits Number of bits of oversampling.
*/
void SetOversampleBits(int bits);
/**
* Get the number of oversample bits previously configured.
*
* 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 Number of bits of oversampling previously configured.
*/
int GetOversampleBits() const;
/**
* Get the factory scaling least significant bit weight constant.
*
* Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
*
* @return Least significant bit weight.
*/
int GetLSBWeight() const;
/**
* Get the factory scaling offset constant.
*
* Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
*
* @return Offset constant.
*/
int GetOffset() const;
/**
* Set the sample rate per channel for all analog channels.
*
* The maximum rate is 500kS/s divided by the number of channels in use.
* This is 62500 samples/s per channel.
*
* @param samplesPerSecond The number of samples per second.
*/
static void SetSampleRate(double samplesPerSecond);
/**
* Get the current sample rate for all channels
*
* @return Sample rate.
*/
static double GetSampleRate();
/** /**
* Indicates this input is used by a simulated device. * Indicates this input is used by a simulated device.
* *

View File

@@ -16,12 +16,7 @@ namespace wpi {
class AddressableLED; class AddressableLED;
/** /**
* Class implements the PWM generation in the FPGA. * Class for sending pulse-width modulation (PWM) signals.
*
* The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They
* are mapped to the microseconds to keep the pulse high, with a range of 0
* (off) to 4096. Changes are immediately sent to the FPGA, and the update
* occurs at the next FPGA cycle (5.05ms). There is no delay.
*/ */
class PWM : public wpi::util::Sendable, public wpi::util::SendableHelper<PWM> { class PWM : public wpi::util::Sendable, public wpi::util::SendableHelper<PWM> {
public: public:

View File

@@ -59,58 +59,6 @@ class AnalogInputSim {
*/ */
void SetInitialized(bool initialized); void SetInitialized(bool 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 CallbackStore object associated with this callback
*/
[[nodiscard]]
std::unique_ptr<CallbackStore> RegisterAverageBitsCallback(
NotifyCallback callback, bool initialNotify);
/**
* Get the number of average bits.
*
* @return the number of average bits
*/
int GetAverageBits() const;
/**
* Change the number of average bits.
*
* @param averageBits the new value
*/
void SetAverageBits(int 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 CallbackStore object associated with this callback
*/
[[nodiscard]]
std::unique_ptr<CallbackStore> RegisterOversampleBitsCallback(
NotifyCallback callback, bool initialNotify);
/**
* Get the amount of oversampling bits.
*
* @return the amount of oversampling bits
*/
int GetOversampleBits() const;
/**
* Change the amount of oversampling bits.
*
* @param oversampleBits the new value
*/
void SetOversampleBits(int oversampleBits);
/** /**
* Register a callback on the voltage. * Register a callback on the voltage.
* *

View File

@@ -9,12 +9,9 @@ namespace wpi {
* Runtime type. * Runtime type.
*/ */
enum class RuntimeType { enum class RuntimeType {
/// roboRIO 1.0. /// Systemcore runtime.
ROBORIO, SYSTEMCORE,
/// roboRIO 2.0.
ROBORIO_2,
/// Simulation runtime. /// Simulation runtime.
SIMULATION, SIMULATION
SYSTEMCORE
}; };
} // namespace wpi } // namespace wpi

View File

@@ -28,39 +28,7 @@ class SensorUtil final {
*/ */
static int GetDefaultREVPHModule(); static int GetDefaultREVPHModule();
/** static int GetNumSmartIoPorts();
* 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.
*
* @return Digital channel is valid
*/
static bool CheckDigitalChannel(int channel);
/**
* 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.
*
* @return PWM channel is valid
*/
static bool CheckPWMChannel(int channel);
/**
* 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.
*
* @return Analog channel is valid
*/
static bool CheckAnalogInputChannel(int channel);
static int GetNumDigitalChannels();
static int GetNumAnalogInputs();
static int GetNumPwmChannels();
}; };
} // namespace wpi } // namespace wpi

View File

@@ -8,18 +8,8 @@ classes:
methods: methods:
AnalogInput: AnalogInput:
GetValue: GetValue:
GetAverageValue:
GetVoltage: GetVoltage:
GetAverageVoltage:
GetChannel: GetChannel:
SetAverageBits:
GetAverageBits:
SetOversampleBits:
GetOversampleBits:
GetLSBWeight:
GetOffset:
SetSampleRate:
GetSampleRate:
SetSimDevice: SetSimDevice:
InitSendable: InitSendable:

View File

@@ -2,11 +2,6 @@ classes:
wpi::SensorUtil: wpi::SensorUtil:
nodelete: true nodelete: true
methods: methods:
CheckDigitalChannel:
CheckPWMChannel:
CheckAnalogInputChannel:
GetDefaultCTREPCMModule: GetDefaultCTREPCMModule:
GetDefaultREVPHModule: GetDefaultREVPHModule:
GetNumDigitalChannels: GetNumSmartIoPorts:
GetNumAnalogInputs:
GetNumPwmChannels:

View File

@@ -13,12 +13,6 @@ classes:
RegisterInitializedCallback: RegisterInitializedCallback:
GetInitialized: GetInitialized:
SetInitialized: SetInitialized:
RegisterAverageBitsCallback:
GetAverageBits:
SetAverageBits:
RegisterOversampleBitsCallback:
GetOversampleBits:
SetOversampleBits:
RegisterVoltageCallback: RegisterVoltageCallback:
GetVoltage: GetVoltage:
SetVoltage: SetVoltage:

View File

@@ -62,34 +62,4 @@ TEST(AnalogInputSimTest, SetVoltage) {
} }
} }
TEST(AnalogInputSimTest, SetOverSampleBits) {
HAL_Initialize(500, 0);
AnalogInput input{5};
AnalogInputSim sim(input);
IntCallback callback;
auto cb = sim.RegisterOversampleBitsCallback(callback.GetCallback(), false);
input.SetOversampleBits(3504);
EXPECT_EQ(3504, sim.GetOversampleBits());
EXPECT_EQ(3504, input.GetOversampleBits());
EXPECT_TRUE(callback.WasTriggered());
EXPECT_EQ(3504, callback.GetLastValue());
}
TEST(AnalogInputSimTest, SetAverageBits) {
HAL_Initialize(500, 0);
AnalogInput input{5};
AnalogInputSim sim(input);
IntCallback callback;
auto cb = sim.RegisterAverageBitsCallback(callback.GetCallback(), false);
input.SetAverageBits(3504);
EXPECT_EQ(3504, sim.GetAverageBits());
EXPECT_EQ(3504, input.GetAverageBits());
EXPECT_TRUE(callback.WasTriggered());
EXPECT_EQ(3504, callback.GetLastValue());
}
} // namespace wpi::sim } // namespace wpi::sim

View File

@@ -12,16 +12,6 @@
class Robot : public wpi::TimedRobot { class Robot : public wpi::TimedRobot {
public: public:
Robot() { Robot() {
// Sets the AnalogInput to 4-bit oversampling. 16 samples will be added
// together.
// Thus, the reported values will increase by about a factor of 16, and the
// update rate will decrease by a similar amount.
m_analog.SetOversampleBits(4);
// Sets the AnalogInput to 4-bit averaging. 16 samples will be averaged
// together. The update rate will decrease by a factor of 16.
m_analog.SetAverageBits(4);
// Gets the raw instantaneous measured value from the analog input, without // Gets the raw instantaneous measured value from the analog input, without
// applying any calibration and ignoring oversampling and averaging // applying any calibration and ignoring oversampling and averaging
// settings. // settings.
@@ -30,14 +20,6 @@ class Robot : public wpi::TimedRobot {
// Gets the instantaneous measured voltage from the analog input. // Gets the instantaneous measured voltage from the analog input.
// Oversampling and averaging settings are ignored // Oversampling and averaging settings are ignored
m_analog.GetVoltage(); m_analog.GetVoltage();
// Gets the averaged value from the analog input. The value is not
// rescaled, but oversampling and averaging are both applied.
m_analog.GetAverageValue();
// Gets the averaged voltage from the analog input. Rescaling,
// oversampling, and averaging are all applied.
m_analog.GetAverageVoltage();
} }
void TeleopPeriodic() override {} void TeleopPeriodic() override {}

View File

@@ -12,10 +12,7 @@
*/ */
class Robot : public wpi::TimedRobot { class Robot : public wpi::TimedRobot {
public: public:
Robot() { Robot() {}
// Set averaging bits to 2
m_input.SetAverageBits(2);
}
void TeleopPeriodic() override { void TeleopPeriodic() override {
// Get the value of the potentiometer // Get the value of the potentiometer

View File

@@ -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 * Get a scaled sample straight from this channel. The value is scaled to units of Volts.
* 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().
* *
* @return A scaled sample straight from this channel. * @return A scaled sample straight from this channel.
*/ */
@@ -79,43 +64,6 @@ public class AnalogInput implements Sendable, AutoCloseable {
return AnalogInputJNI.getAnalogVoltage(m_port); 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. * Get the channel number.
* *
@@ -125,70 +73,6 @@ public class AnalogInput implements Sendable, AutoCloseable {
return m_channel; 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. * Indicates this input is used by a simulated device.
* *
@@ -201,6 +85,6 @@ public class AnalogInput implements Sendable, AutoCloseable {
@Override @Override
public void initSendable(SendableBuilder builder) { public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("Analog Input"); builder.setSmartDashboardType("Analog Input");
builder.addDoubleProperty("Value", this::getAverageVoltage, null); builder.addDoubleProperty("Value", this::getVoltage, null);
} }
} }

View File

@@ -7,7 +7,6 @@ package org.wpilib.hardware.discrete;
import org.wpilib.hardware.hal.DIOJNI; import org.wpilib.hardware.hal.DIOJNI;
import org.wpilib.hardware.hal.HAL; import org.wpilib.hardware.hal.HAL;
import org.wpilib.hardware.hal.SimDevice; import org.wpilib.hardware.hal.SimDevice;
import org.wpilib.system.SensorUtil;
import org.wpilib.util.sendable.Sendable; import org.wpilib.util.sendable.Sendable;
import org.wpilib.util.sendable.SendableBuilder; import org.wpilib.util.sendable.SendableBuilder;
import org.wpilib.util.sendable.SendableRegistry; import org.wpilib.util.sendable.SendableRegistry;
@@ -29,7 +28,6 @@ public class DigitalInput implements AutoCloseable, Sendable {
*/ */
@SuppressWarnings("this-escape") @SuppressWarnings("this-escape")
public DigitalInput(int channel) { public DigitalInput(int channel) {
SensorUtil.checkDigitalChannel(channel);
m_channel = channel; m_channel = channel;
m_handle = DIOJNI.initializeDIOPort(channel, true); m_handle = DIOJNI.initializeDIOPort(channel, true);

View File

@@ -7,7 +7,6 @@ package org.wpilib.hardware.discrete;
import org.wpilib.hardware.hal.DIOJNI; import org.wpilib.hardware.hal.DIOJNI;
import org.wpilib.hardware.hal.HAL; import org.wpilib.hardware.hal.HAL;
import org.wpilib.hardware.hal.SimDevice; import org.wpilib.hardware.hal.SimDevice;
import org.wpilib.system.SensorUtil;
import org.wpilib.util.sendable.Sendable; import org.wpilib.util.sendable.Sendable;
import org.wpilib.util.sendable.SendableBuilder; import org.wpilib.util.sendable.SendableBuilder;
import org.wpilib.util.sendable.SendableRegistry; import org.wpilib.util.sendable.SendableRegistry;
@@ -30,7 +29,6 @@ public class DigitalOutput implements AutoCloseable, Sendable {
*/ */
@SuppressWarnings("this-escape") @SuppressWarnings("this-escape")
public DigitalOutput(int channel) { public DigitalOutput(int channel) {
SensorUtil.checkDigitalChannel(channel);
m_channel = channel; m_channel = channel;
m_handle = DIOJNI.initializeDIOPort(channel, false); m_handle = DIOJNI.initializeDIOPort(channel, false);
@@ -161,8 +159,6 @@ public class DigitalOutput implements AutoCloseable, Sendable {
if (m_pwmGenerator == invalidPwmGenerator) { if (m_pwmGenerator == invalidPwmGenerator) {
return; return;
} }
// Disable the output by routing to a dead bit.
DIOJNI.setDigitalPWMOutputChannel(m_pwmGenerator, SensorUtil.NUM_DIGITAL_CHANNELS);
DIOJNI.freeDigitalPWM(m_pwmGenerator); DIOJNI.freeDigitalPWM(m_pwmGenerator);
m_pwmGenerator = invalidPwmGenerator; m_pwmGenerator = invalidPwmGenerator;
} }

View File

@@ -7,7 +7,6 @@ package org.wpilib.hardware.discrete;
import org.wpilib.hardware.hal.HAL; import org.wpilib.hardware.hal.HAL;
import org.wpilib.hardware.hal.PWMJNI; import org.wpilib.hardware.hal.PWMJNI;
import org.wpilib.hardware.hal.SimDevice; import org.wpilib.hardware.hal.SimDevice;
import org.wpilib.system.SensorUtil;
import org.wpilib.util.sendable.Sendable; import org.wpilib.util.sendable.Sendable;
import org.wpilib.util.sendable.SendableBuilder; import org.wpilib.util.sendable.SendableBuilder;
import org.wpilib.util.sendable.SendableRegistry; import org.wpilib.util.sendable.SendableRegistry;
@@ -46,7 +45,6 @@ public class PWM implements Sendable, AutoCloseable {
*/ */
@SuppressWarnings("this-escape") @SuppressWarnings("this-escape")
public PWM(final int channel, final boolean registerSendable) { public PWM(final int channel, final boolean registerSendable) {
SensorUtil.checkPWMChannel(channel);
m_channel = channel; m_channel = channel;
m_handle = PWMJNI.initializePWMPort(channel); m_handle = PWMJNI.initializePWMPort(channel);

View File

@@ -60,67 +60,6 @@ public class AnalogInputSim {
AnalogInDataJNI.setInitialized(m_index, initialized); 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. * Register a callback on the voltage.
* *

View File

@@ -8,14 +8,10 @@ import org.wpilib.hardware.hal.HALUtil;
/** Runtime type. */ /** Runtime type. */
public enum RuntimeType { public enum RuntimeType {
/** roboRIO 1.0. */ /** Systemcore runtime. */
ROBORIO(HALUtil.RUNTIME_ROBORIO), SYSTEMCORE(HALUtil.RUNTIME_SYSTEMCORE),
/** roboRIO 2.0. */
ROBORIO_2(HALUtil.RUNTIME_ROBORIO_2),
/** Simulation runtime. */ /** Simulation runtime. */
SIMULATION(HALUtil.RUNTIME_SIMULATION), SIMULATION(HALUtil.RUNTIME_SIMULATION);
/** Systemcore. */
SYSTEMCORE(HALUtil.RUNTIME_SYSTEMCORE);
/** RuntimeType value. */ /** RuntimeType value. */
public final int value; public final int value;
@@ -31,11 +27,10 @@ public enum RuntimeType {
* @return Matching runtime type * @return Matching runtime type
*/ */
public static RuntimeType getValue(int type) { public static RuntimeType getValue(int type) {
return switch (type) { if (type == HALUtil.RUNTIME_SYSTEMCORE) {
case HALUtil.RUNTIME_ROBORIO -> RuntimeType.ROBORIO; return RuntimeType.SYSTEMCORE;
case HALUtil.RUNTIME_ROBORIO_2 -> RuntimeType.ROBORIO_2; } else {
case HALUtil.RUNTIME_SYSTEMCORE -> RuntimeType.SYSTEMCORE; return RuntimeType.SIMULATION;
default -> RuntimeType.SIMULATION; }
};
} }
} }

View File

@@ -4,10 +4,6 @@
package org.wpilib.system; 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; import org.wpilib.hardware.hal.PortsJNI;
/** /**
@@ -15,22 +11,12 @@ import org.wpilib.hardware.hal.PortsJNI;
* channels and error processing. * channels and error processing.
*/ */
public final class SensorUtil { public final class SensorUtil {
/** Ticks per microsecond. */ /** Number of SmartIo Ports. */
public static final int SYSTEM_CLOCK_TICKS_PER_MICROSECOND = public static final int kSmartIoPorts = PortsJNI.getNumSmartIo();
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 solenoid channels per module. */ /** Number of solenoid channels per module. */
public static final int NUM_CTRE_SOLENOID_CHANNELS = PortsJNI.getNumCTRESolenoidChannels(); 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. */ /** Number of power distribution channels per PDP. */
public static final int NUM_CTRE_PDP_CHANNELS = PortsJNI.getNumCTREPDPChannels(); public static final int NUM_CTRE_PDP_CHANNELS = PortsJNI.getNumCTREPDPChannels();
@@ -46,57 +32,6 @@ public final class SensorUtil {
/** Number of PH modules. */ /** Number of PH modules. */
public static final int NUM_REV_PH_MODULES = PortsJNI.getNumREVPHModules(); 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. * Get the number of the default solenoid module.
* *

View File

@@ -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());
}
}
} }

View File

@@ -5,26 +5,10 @@
package org.wpilib.system; package org.wpilib.system;
import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertThrows;
import org.junit.jupiter.api.Test; import org.junit.jupiter.api.Test;
class SensorUtilTest { 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 @Test
void testgetDefaultCtrePcmModule() { void testgetDefaultCtrePcmModule() {
assertEquals(0, SensorUtil.getDefaultCTREPCMModule()); assertEquals(0, SensorUtil.getDefaultCTREPCMModule());

View File

@@ -16,16 +16,7 @@ public class Robot extends TimedRobot {
AnalogInput m_analog = new AnalogInput(0); AnalogInput m_analog = new AnalogInput(0);
/** Called once at the beginning of the robot program. */ /** Called once at the beginning of the robot program. */
public Robot() { public Robot() {}
// Sets the AnalogInput to 4-bit oversampling. 16 samples will be added together.
// Thus, the reported values will increase by about a factor of 16, and the update
// rate will decrease by a similar amount.
m_analog.setOversampleBits(4);
// Sets the AnalogInput to 4-bit averaging. 16 samples will be averaged together.
// The update rate will decrease by a factor of 16.
m_analog.setAverageBits(4);
}
@Override @Override
public void teleopPeriodic() { public void teleopPeriodic() {
@@ -37,13 +28,5 @@ public class Robot extends TimedRobot {
// Gets the instantaneous measured voltage from the analog input. // Gets the instantaneous measured voltage from the analog input.
// Oversampling and averaging settings are ignored // Oversampling and averaging settings are ignored
m_analog.getVoltage(); m_analog.getVoltage();
// Gets the averaged value from the analog input. The value is not
// rescaled, but oversampling and averaging are both applied.
m_analog.getAverageValue();
// Gets the averaged voltage from the analog input. Rescaling,
// oversampling, and averaging are all applied.
m_analog.getAverageVoltage();
} }
} }

View File

@@ -30,10 +30,7 @@ public class Robot extends TimedRobot {
AnalogPotentiometer m_pot1 = new AnalogPotentiometer(m_input, 180, 30); AnalogPotentiometer m_pot1 = new AnalogPotentiometer(m_input, 180, 30);
/** Called once at the beginning of the robot program. */ /** Called once at the beginning of the robot program. */
public Robot() { public Robot() {}
// Set averaging bits to 2
m_input.setAverageBits(2);
}
@Override @Override
public void teleopPeriodic() { public void teleopPeriodic() {

View File

@@ -27,11 +27,10 @@ import org.wpilib.util.container.DoubleCircularBuffer;
* impact of these high frequency components. Likewise, a "high pass" filter gets rid of slow-moving * impact of these high frequency components. Likewise, a "high pass" filter gets rid of slow-moving
* signal components, letting you detect large changes more easily. * signal components, letting you detect large changes more easily.
* *
* <p>Example FRC applications of filters: - Getting rid of noise from an analog sensor input (note: * <p>Example FRC applications of filters: - Getting rid of noise from an analog sensor input -
* the roboRIO's FPGA can do this faster in hardware) - Smoothing out joystick input to prevent the * Smoothing out joystick input to prevent the wheels from slipping or the robot from tipping -
* wheels from slipping or the robot from tipping - Smoothing motor commands so that unnecessary * Smoothing motor commands so that unnecessary strain isn't put on electrical or mechanical
* strain isn't put on electrical or mechanical components - If you use clever gains, you can make a * components - If you use clever gains, you can make a PID controller out of this class!
* PID controller out of this class!
* *
* <p>For more on filters, we highly recommend the following articles:<br> * <p>For more on filters, we highly recommend the following articles:<br>
* <a * <a

View File

@@ -49,8 +49,7 @@ namespace wpi::math {
* components, letting you detect large changes more easily. * components, letting you detect large changes more easily.
* *
* Example FRC applications of filters: * Example FRC applications of filters:
* - Getting rid of noise from an analog sensor input (note: the roboRIO's FPGA * - Getting rid of noise from an analog sensor input
* can do this faster in hardware)
* - Smoothing out joystick input to prevent the wheels from slipping or the * - Smoothing out joystick input to prevent the wheels from slipping or the
* robot from tipping * robot from tipping
* - Smoothing motor commands so that unnecessary strain isn't put on * - Smoothing motor commands so that unnecessary strain isn't put on