001 /*----------------------------------------------------------------------------*/ 002 /* Copyright (c) FIRST 2008-2012. 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 package edu.wpi.first.wpilibj; 008 009 import edu.wpi.first.wpilibj.communication.UsageReporting; 010 import edu.wpi.first.wpilibj.fpga.tAccumulator; 011 import edu.wpi.first.wpilibj.livewindow.LiveWindow; 012 import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable; 013 import edu.wpi.first.wpilibj.tables.ITable; 014 import edu.wpi.first.wpilibj.util.AllocationException; 015 import edu.wpi.first.wpilibj.util.CheckedAllocationException; 016 017 /** 018 * Analog channel class. 019 * 020 * Each analog channel is read from hardware as a 12-bit number representing -10V to 10V. 021 * 022 * Connected to each analog channel is an averaging and oversampling engine. This engine accumulates 023 * the specified ( by setAverageBits() and setOversampleBits() ) number of samples before returning a new 024 * value. This is not a sliding window average. The only difference between the oversampled samples and 025 * the averaged samples is that the oversampled samples are simply accumulated effectively increasing the 026 * resolution, while the averaged samples are divided by the number of samples to retain the resolution, 027 * but get more stable values. 028 */ 029 public class AnalogChannel extends SensorBase implements PIDSource, LiveWindowSendable { 030 031 private static final int kAccumulatorSlot = 1; 032 private static Resource channels = new Resource(kAnalogModules * kAnalogChannels); 033 private int m_channel; 034 private int m_moduleNumber; 035 private AnalogModule m_module; 036 private static final int[] kAccumulatorChannels = { 037 1, 2 038 }; 039 private tAccumulator m_accumulator; 040 private long m_accumulatorOffset; 041 private boolean m_shouldUseVoltageForPID; 042 043 /** 044 * Construct an analog channel on the default module. 045 * 046 * @param channel The channel number to represent. 047 */ 048 public AnalogChannel(final int channel) { 049 this(getDefaultAnalogModule(), channel); 050 } 051 052 /** 053 * Construct an analog channel on a specified module. 054 * 055 * @param moduleNumber The digital module to use (1 or 2). 056 * @param channel The channel number to represent. 057 */ 058 public AnalogChannel(final int moduleNumber, final int channel) { 059 m_shouldUseVoltageForPID = false; 060 checkAnalogModule(moduleNumber); 061 checkAnalogChannel(channel); 062 m_channel = channel; 063 m_moduleNumber = moduleNumber; 064 m_module = AnalogModule.getInstance(moduleNumber); 065 try { 066 channels.allocate((moduleNumber - 1) * kAnalogChannels + m_channel - 1); 067 } catch (CheckedAllocationException e) { 068 throw new AllocationException( 069 "Analog channel " + m_channel + " on module " + m_moduleNumber + " is already allocated"); 070 } 071 if (channel == 1 || channel == 2) { 072 m_accumulator = new tAccumulator((byte) (channel - 1)); 073 m_accumulatorOffset = 0; 074 } else { 075 m_accumulator = null; 076 } 077 078 LiveWindow.addSensor("Analog", moduleNumber, channel, this); 079 UsageReporting.report(UsageReporting.kResourceType_AnalogChannel, channel, m_moduleNumber-1); 080 } 081 082 /** 083 * Channel destructor. 084 */ 085 public void free() { 086 channels.free(((m_moduleNumber - 1) * kAnalogChannels + m_channel - 1)); 087 m_channel = 0; 088 m_moduleNumber = 0; 089 // m_accumulator.Release(); 090 m_accumulator = null; 091 m_accumulatorOffset = 0; 092 } 093 094 /** 095 * Get the analog module that this channel is on. 096 * @return The AnalogModule that this channel is on. 097 */ 098 public AnalogModule getModule() { 099 return m_module; 100 } 101 102 /** 103 * Get a sample straight from this channel on the module. 104 * The sample is a 12-bit value representing the -10V to 10V range of the A/D converter in the module. 105 * The units are in A/D converter codes. Use GetVoltage() to get the analog value in calibrated units. 106 * @return A sample straight from this channel on the module. 107 */ 108 public int getValue() { 109 return m_module.getValue(m_channel); 110 } 111 112 /** 113 * Get a sample from the output of the oversample and average engine for this channel. 114 * The sample is 12-bit + the value configured in SetOversampleBits(). 115 * The value configured in setAverageBits() will cause this value to be averaged 2**bits number of samples. 116 * This is not a sliding window. The sample will not change until 2**(OversamplBits + AverageBits) samples 117 * have been acquired from the module on this channel. 118 * Use getAverageVoltage() to get the analog value in calibrated units. 119 * @return A sample from the oversample and average engine for this channel. 120 */ 121 public int getAverageValue() { 122 return m_module.getAverageValue(m_channel); 123 124 } 125 126 /** 127 * Get a scaled sample straight from this channel on the module. 128 * The value is scaled to units of Volts using the calibrated scaling data from getLSBWeight() and getOffset(). 129 * @return A scaled sample straight from this channel on the module. 130 */ 131 public double getVoltage() { 132 return m_module.getVoltage(m_channel); 133 } 134 135 /** 136 * Get a scaled sample from the output of the oversample and average engine for this channel. 137 * The value is scaled to units of Volts using the calibrated scaling data from getLSBWeight() and getOffset(). 138 * Using oversampling will cause this value to be higher resolution, but it will update more slowly. 139 * Using averaging will cause this value to be more stable, but it will update more slowly. 140 * @return A scaled sample from the output of the oversample and average engine for this channel. 141 */ 142 public double getAverageVoltage() { 143 return m_module.getAverageVoltage(m_channel); 144 } 145 146 /** 147 * Get the factory scaling least significant bit weight constant. 148 * The least significant bit weight constant for the channel that was calibrated in 149 * manufacturing and stored in an eeprom in the module. 150 * 151 * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9) 152 * 153 * @return Least significant bit weight. 154 */ 155 public long getLSBWeight() { 156 return m_module.getLSBWeight(m_channel); 157 } 158 159 /** 160 * Get the factory scaling offset constant. 161 * The offset constant for the channel that was calibrated in manufacturing and stored 162 * in an eeprom in the module. 163 * 164 * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9) 165 * 166 * @return Offset constant. 167 */ 168 public int getOffset() { 169 return m_module.getOffset(m_channel); 170 } 171 172 /** 173 * Get the channel number. 174 * @return The channel number. 175 */ 176 public int getChannel() { 177 return m_channel; 178 } 179 180 /** 181 * Gets the number of the analog module this channel is on. 182 * @return The module number of the analog module this channel is on. 183 */ 184 public int getModuleNumber() { 185 return m_module.getModuleNumber(); 186 } 187 188 /** 189 * Set the number of averaging bits. 190 * This sets the number of averaging bits. The actual number of averaged samples is 2**bits. 191 * The averaging is done automatically in the FPGA. 192 * 193 * @param bits The number of averaging bits. 194 */ 195 public void setAverageBits(final int bits) { 196 m_module.setAverageBits(m_channel, bits); 197 } 198 199 /** 200 * Get the number of averaging bits. 201 * This gets the number of averaging bits from the FPGA. The actual number of averaged samples is 2**bits. 202 * The averaging is done automatically in the FPGA. 203 * 204 * @return The number of averaging bits. 205 */ 206 public int getAverageBits() { 207 return m_module.getAverageBits(m_channel); 208 } 209 210 /** 211 * Set the number of oversample bits. 212 * This sets the number of oversample bits. The actual number of oversampled values is 213 * 2**bits. The oversampling is done automatically in the FPGA. 214 * 215 * @param bits The number of oversample bits. 216 */ 217 public void setOversampleBits(final int bits) { 218 m_module.setOversampleBits(m_channel, bits); 219 } 220 221 /** 222 * Get the number of oversample bits. 223 * This gets the number of oversample bits from the FPGA. The actual number of oversampled values is 224 * 2**bits. The oversampling is done automatically in the FPGA. 225 * 226 * @return The number of oversample bits. 227 */ 228 public int getOversampleBits() { 229 return m_module.getOversampleBits(m_channel); 230 } 231 232 /** 233 * Initialize the accumulator. 234 */ 235 public void initAccumulator() { 236 if (!isAccumulatorChannel()) { 237 throw new AllocationException( 238 "Accumulators are only available on slot " + 239 kAccumulatorSlot + " on channels " + kAccumulatorChannels[0] + "," + kAccumulatorChannels[1]); 240 } 241 m_accumulatorOffset = 0; 242 setAccumulatorCenter(0); 243 resetAccumulator(); 244 } 245 246 /** 247 * Set an inital value for the accumulator. 248 * 249 * This will be added to all values returned to the user. 250 * @param initialValue The value that the accumulator should start from when reset. 251 */ 252 public void setAccumulatorInitialValue(long initialValue) { 253 m_accumulatorOffset = initialValue; 254 } 255 256 /** 257 * Resets the accumulator to the initial value. 258 */ 259 public void resetAccumulator() { 260 m_accumulator.strobeReset(); 261 } 262 263 /** 264 * Set the center value of the accumulator. 265 * 266 * The center value is subtracted from each A/D value before it is added to the accumulator. This 267 * is used for the center value of devices like gyros and accelerometers to make integration work 268 * and to take the device offset into account when integrating. 269 * 270 * This center value is based on the output of the oversampled and averaged source from channel 1. 271 * Because of this, any non-zero oversample bits will affect the size of the value for this field. 272 */ 273 public void setAccumulatorCenter(int center) { 274 m_accumulator.writeCenter(center); 275 } 276 277 /** 278 * Set the accumulator's deadband. 279 */ 280 public void setAccumulatorDeadband(int deadband) { 281 m_accumulator.writeDeadband(deadband); 282 } 283 284 /** 285 * Read the accumulated value. 286 * 287 * Read the value that has been accumulating on channel 1. 288 * The accumulator is attached after the oversample and average engine. 289 * 290 * @return The 64-bit value accumulated since the last Reset(). 291 */ 292 public long getAccumulatorValue() { 293 long value = m_accumulator.readOutput_Value() + m_accumulatorOffset; 294 return value; 295 } 296 297 /** 298 * Read the number of accumulated values. 299 * 300 * Read the count of the accumulated values since the accumulator was last Reset(). 301 * 302 * @return The number of times samples from the channel were accumulated. 303 */ 304 public long getAccumulatorCount() { 305 long count = m_accumulator.readOutput_Count(); 306 return count; 307 } 308 309 /** 310 * Read the accumulated value and the number of accumulated values atomically. 311 * 312 * This function reads the value and count from the FPGA atomically. 313 * This can be used for averaging. 314 * 315 * @param result AccumulatorResult object to store the results in. 316 */ 317 public void getAccumulatorOutput(AccumulatorResult result) { 318 if (result == null) { 319 System.out.println("Null result in getAccumulatorOutput"); 320 } 321 if (m_accumulator == null) { 322 System.out.println("Null m_accumulator in getAccumulatorOutput"); 323 } 324 result.value = m_accumulator.readOutput_Value() + m_accumulatorOffset; 325 result.count = m_accumulator.readOutput_Count(); 326 } 327 328 /** 329 * Is the channel attached to an accumulator. 330 * 331 * @return The analog channel is attached to an accumulator. 332 */ 333 public boolean isAccumulatorChannel() { 334 if (m_module.getModuleNumber() != kAccumulatorSlot) { 335 return false; 336 } 337 for (int i = 0; i < kAccumulatorChannels.length; i++) { 338 if (m_channel == kAccumulatorChannels[i]) { 339 return true; 340 } 341 } 342 return false; 343 } 344 345 /** 346 * Set whether to use voltage of value for PIDGet 347 * This method determines whether PIDGet uses average voltage or value for 348 * PID controllers for a particular channel. This is to preserve compatibility 349 * with existing programs and is likely to change in favor of voltage for 350 * RoboRIO. 351 * @param m_shouldUseVoltageForPID True if voltage should be used for PIDGet. The 352 * default is to use the value as it has been since the creation of the library. 353 */ 354 public void setVoltageForPID(boolean shouldUseVoltageForPID) { 355 m_shouldUseVoltageForPID = shouldUseVoltageForPID; 356 } 357 358 /** 359 * Get the average value for use with PIDController. 360 * This can be changed to use average voltage by calling setVoltageForPID(). 361 * @return the average value 362 */ 363 public double pidGet() { 364 if (m_shouldUseVoltageForPID) { 365 return getAverageVoltage(); 366 } 367 else { 368 return getAverageValue(); 369 } 370 } 371 372 /* 373 * Live Window code, only does anything if live window is activated. 374 */ 375 public String getSmartDashboardType(){ 376 return "Analog Input"; 377 } 378 private ITable m_table; 379 380 /** 381 * {@inheritDoc} 382 */ 383 public void initTable(ITable subtable) { 384 m_table = subtable; 385 updateTable(); 386 } 387 388 /** 389 * {@inheritDoc} 390 */ 391 public void updateTable() { 392 if (m_table != null) { 393 m_table.putNumber("Value", getAverageVoltage()); 394 } 395 } 396 397 /** 398 * {@inheritDoc} 399 */ 400 public ITable getTable(){ 401 return m_table; 402 } 403 404 /** 405 * Analog Channels don't have to do anything special when entering the LiveWindow. 406 * {@inheritDoc} 407 */ 408 public void startLiveWindowMode() {} 409 410 /** 411 * Analog Channels don't have to do anything special when exiting the LiveWindow. 412 * {@inheritDoc} 413 */ 414 public void stopLiveWindowMode() {} 415 }