001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.wpilibj; 006 007import edu.wpi.first.hal.AccumulatorResult; 008import edu.wpi.first.hal.AnalogJNI; 009import edu.wpi.first.hal.FRCNetComm.tResourceType; 010import edu.wpi.first.hal.HAL; 011import edu.wpi.first.hal.SimDevice; 012import edu.wpi.first.hal.util.AllocationException; 013import edu.wpi.first.util.sendable.Sendable; 014import edu.wpi.first.util.sendable.SendableBuilder; 015import edu.wpi.first.util.sendable.SendableRegistry; 016 017/** 018 * Analog channel class. 019 * 020 * <p>Each analog channel is read from hardware as a 12-bit number representing 0V to 5V. 021 * 022 * <p>Connected to each analog channel is an averaging and oversampling engine. This engine 023 * accumulates the specified ( by setAverageBits() and setOversampleBits() ) number of samples 024 * before returning a new value. This is not a sliding window average. The only difference between 025 * the oversampled samples and the averaged samples is that the oversampled samples are simply 026 * accumulated effectively increasing the resolution, while the averaged samples are divided by the 027 * number of samples to retain the resolution, but get more stable values. 028 */ 029public class AnalogInput implements Sendable, AutoCloseable { 030 private static final int kAccumulatorSlot = 1; 031 int m_port; // explicit no modifier, private and package accessible. 032 private int m_channel; 033 private static final int[] kAccumulatorChannels = {0, 1}; 034 private long m_accumulatorOffset; 035 036 /** 037 * Construct an analog channel. 038 * 039 * @param channel The channel number to represent. 0-3 are on-board 4-7 are on the MXP port. 040 */ 041 public AnalogInput(final int channel) { 042 AnalogJNI.checkAnalogInputChannel(channel); 043 m_channel = channel; 044 045 final int portHandle = HAL.getPort((byte) channel); 046 m_port = AnalogJNI.initializeAnalogInputPort(portHandle); 047 048 HAL.report(tResourceType.kResourceType_AnalogChannel, channel + 1); 049 SendableRegistry.addLW(this, "AnalogInput", channel); 050 } 051 052 @Override 053 public void close() { 054 SendableRegistry.remove(this); 055 AnalogJNI.freeAnalogInputPort(m_port); 056 m_port = 0; 057 m_channel = 0; 058 m_accumulatorOffset = 0; 059 } 060 061 /** 062 * Get a sample straight from this channel. The sample is a 12-bit value representing the 0V to 5V 063 * range of the A/D converter. The units are in A/D converter codes. Use GetVoltage() to get the 064 * analog value in calibrated units. 065 * 066 * @return A sample straight from this channel. 067 */ 068 public int getValue() { 069 return AnalogJNI.getAnalogValue(m_port); 070 } 071 072 /** 073 * Get a sample from the output of the oversample and average engine for this channel. The sample 074 * is 12-bit + the bits configured in SetOversampleBits(). The value configured in 075 * setAverageBits() will cause this value to be averaged 2^bits number of samples. This is not a 076 * sliding window. The sample will not change until 2^(OversampleBits + AverageBits) samples have 077 * been acquired from this channel. Use getAverageVoltage() to get the analog value in calibrated 078 * units. 079 * 080 * @return A sample from the oversample and average engine for this channel. 081 */ 082 public int getAverageValue() { 083 return AnalogJNI.getAnalogAverageValue(m_port); 084 } 085 086 /** 087 * Get a scaled sample straight from this channel. The value is scaled to units of Volts using the 088 * calibrated scaling data from getLSBWeight() and getOffset(). 089 * 090 * @return A scaled sample straight from this channel. 091 */ 092 public double getVoltage() { 093 return AnalogJNI.getAnalogVoltage(m_port); 094 } 095 096 /** 097 * Get a scaled sample from the output of the oversample and average engine for this channel. The 098 * value is scaled to units of Volts using the calibrated scaling data from getLSBWeight() and 099 * getOffset(). Using oversampling will cause this value to be higher resolution, but it will 100 * update more slowly. Using averaging will cause this value to be more stable, but it will update 101 * more slowly. 102 * 103 * @return A scaled sample from the output of the oversample and average engine for this channel. 104 */ 105 public double getAverageVoltage() { 106 return AnalogJNI.getAnalogAverageVoltage(m_port); 107 } 108 109 /** 110 * Get the factory scaling the least significant bit weight constant. The least significant bit 111 * weight constant for the channel that was calibrated in manufacturing and stored in an eeprom. 112 * 113 * <p>Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9) 114 * 115 * @return Least significant bit weight. 116 */ 117 public long getLSBWeight() { 118 return AnalogJNI.getAnalogLSBWeight(m_port); 119 } 120 121 /** 122 * Get the factory scaling offset constant. The offset constant for the channel that was 123 * calibrated in manufacturing and stored in an eeprom. 124 * 125 * <p>Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9) 126 * 127 * @return Offset constant. 128 */ 129 public int getOffset() { 130 return AnalogJNI.getAnalogOffset(m_port); 131 } 132 133 /** 134 * Get the channel number. 135 * 136 * @return The channel number. 137 */ 138 public int getChannel() { 139 return m_channel; 140 } 141 142 /** 143 * Set the number of averaging bits. This sets the number of averaging bits. The actual number of 144 * averaged samples is 2^bits. The averaging is done automatically in the FPGA. 145 * 146 * @param bits The number of averaging bits. 147 */ 148 public void setAverageBits(final int bits) { 149 AnalogJNI.setAnalogAverageBits(m_port, bits); 150 } 151 152 /** 153 * Get the number of averaging bits. This gets the number of averaging bits from the FPGA. The 154 * actual number of averaged samples is 2^bits. The averaging is done automatically in the FPGA. 155 * 156 * @return The number of averaging bits. 157 */ 158 public int getAverageBits() { 159 return AnalogJNI.getAnalogAverageBits(m_port); 160 } 161 162 /** 163 * Set the number of oversample bits. This sets the number of oversample bits. The actual number 164 * of oversampled values is 2^bits. The oversampling is done automatically in the FPGA. 165 * 166 * @param bits The number of oversample bits. 167 */ 168 public void setOversampleBits(final int bits) { 169 AnalogJNI.setAnalogOversampleBits(m_port, bits); 170 } 171 172 /** 173 * Get the number of oversample bits. This gets the number of oversample bits from the FPGA. The 174 * actual number of oversampled values is 2^bits. The oversampling is done automatically in the 175 * FPGA. 176 * 177 * @return The number of oversample bits. 178 */ 179 public int getOversampleBits() { 180 return AnalogJNI.getAnalogOversampleBits(m_port); 181 } 182 183 /** Initialize the accumulator. */ 184 public void initAccumulator() { 185 if (!isAccumulatorChannel()) { 186 throw new AllocationException( 187 "Accumulators are only available on slot " 188 + kAccumulatorSlot 189 + " on channels " 190 + kAccumulatorChannels[0] 191 + ", " 192 + kAccumulatorChannels[1]); 193 } 194 m_accumulatorOffset = 0; 195 AnalogJNI.initAccumulator(m_port); 196 } 197 198 /** 199 * Set an initial value for the accumulator. 200 * 201 * <p>This will be added to all values returned to the user. 202 * 203 * @param initialValue The value that the accumulator should start from when reset. 204 */ 205 public void setAccumulatorInitialValue(long initialValue) { 206 m_accumulatorOffset = initialValue; 207 } 208 209 /** Resets the accumulator to the initial value. */ 210 public void resetAccumulator() { 211 AnalogJNI.resetAccumulator(m_port); 212 213 // Wait until the next sample, so the next call to getAccumulator*() 214 // won't have old values. 215 final double sampleTime = 1.0 / getGlobalSampleRate(); 216 final double overSamples = 1 << getOversampleBits(); 217 final double averageSamples = 1 << getAverageBits(); 218 Timer.delay(sampleTime * overSamples * averageSamples); 219 } 220 221 /** 222 * Set the center value of the accumulator. 223 * 224 * <p>The center value is subtracted from each A/D value before it is added to the accumulator. 225 * This is used for the center value of devices like gyros and accelerometers to take the device 226 * offset into account when integrating. 227 * 228 * <p>This center value is based on the output of the oversampled and averaged source the 229 * accumulator channel. Because of this, any non-zero oversample bits will affect the size of the 230 * value for this field. 231 * 232 * @param center The accumulator's center value. 233 */ 234 public void setAccumulatorCenter(int center) { 235 AnalogJNI.setAccumulatorCenter(m_port, center); 236 } 237 238 /** 239 * Set the accumulator's deadband. 240 * 241 * @param deadband The deadband size in ADC codes (12-bit value) 242 */ 243 public void setAccumulatorDeadband(int deadband) { 244 AnalogJNI.setAccumulatorDeadband(m_port, deadband); 245 } 246 247 /** 248 * Read the accumulated value. 249 * 250 * <p>Read the value that has been accumulating. The accumulator is attached after the oversample 251 * and average engine. 252 * 253 * @return The 64-bit value accumulated since the last Reset(). 254 */ 255 public long getAccumulatorValue() { 256 return AnalogJNI.getAccumulatorValue(m_port) + m_accumulatorOffset; 257 } 258 259 /** 260 * Read the number of accumulated values. 261 * 262 * <p>Read the count of the accumulated values since the accumulator was last Reset(). 263 * 264 * @return The number of times samples from the channel were accumulated. 265 */ 266 public long getAccumulatorCount() { 267 return AnalogJNI.getAccumulatorCount(m_port); 268 } 269 270 /** 271 * Read the accumulated value and the number of accumulated values atomically. 272 * 273 * <p>This function reads the value and count from the FPGA atomically. This can be used for 274 * averaging. 275 * 276 * @param result AccumulatorResult object to store the results in. 277 */ 278 public void getAccumulatorOutput(AccumulatorResult result) { 279 if (result == null) { 280 throw new IllegalArgumentException("Null parameter `result'"); 281 } 282 if (!isAccumulatorChannel()) { 283 throw new IllegalArgumentException( 284 "Channel " + m_channel + " is not an accumulator channel."); 285 } 286 AnalogJNI.getAccumulatorOutput(m_port, result); 287 result.value += m_accumulatorOffset; 288 } 289 290 /** 291 * Is the channel attached to an accumulator. 292 * 293 * @return The analog channel is attached to an accumulator. 294 */ 295 public boolean isAccumulatorChannel() { 296 for (int channel : kAccumulatorChannels) { 297 if (m_channel == channel) { 298 return true; 299 } 300 } 301 return false; 302 } 303 304 /** 305 * Set the sample rate per channel. 306 * 307 * <p>This is a global setting for all channels. The maximum rate is 500kS/s divided by the number 308 * of channels in use. This is 62500 samples/s per channel if all 8 channels are used. 309 * 310 * @param samplesPerSecond The number of samples per second. 311 */ 312 public static void setGlobalSampleRate(final double samplesPerSecond) { 313 AnalogJNI.setAnalogSampleRate(samplesPerSecond); 314 } 315 316 /** 317 * Get the current sample rate. 318 * 319 * <p>This assumes one entry in the scan list. This is a global setting for all channels. 320 * 321 * @return Sample rate. 322 */ 323 public static double getGlobalSampleRate() { 324 return AnalogJNI.getAnalogSampleRate(); 325 } 326 327 /** 328 * Indicates this input is used by a simulated device. 329 * 330 * @param device simulated device handle 331 */ 332 public void setSimDevice(SimDevice device) { 333 AnalogJNI.setAnalogInputSimDevice(m_port, device.getNativeHandle()); 334 } 335 336 @Override 337 public void initSendable(SendableBuilder builder) { 338 builder.setSmartDashboardType("Analog Input"); 339 builder.addDoubleProperty("Value", this::getAverageVoltage, null); 340 } 341}