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