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.CTREPCMJNI;
008import java.util.HashMap;
009import java.util.Map;
010
011/** Module class for controlling a Cross The Road Electronics Pneumatics Control Module. */
012public class PneumaticsControlModule implements PneumaticsBase {
013  private static class DataStore implements AutoCloseable {
014    public final int m_module;
015    public final int m_handle;
016    private int m_refCount;
017    private int m_reservedMask;
018    private boolean m_compressorReserved;
019    private final Object m_reserveLock = new Object();
020
021    DataStore(int module) {
022      m_handle = CTREPCMJNI.initialize(module);
023      m_module = module;
024      m_handleMap.put(module, this);
025    }
026
027    @Override
028    public void close() {
029      CTREPCMJNI.free(m_handle);
030      m_handleMap.remove(m_module);
031    }
032
033    public void addRef() {
034      m_refCount++;
035    }
036
037    public void removeRef() {
038      m_refCount--;
039      if (m_refCount == 0) {
040        this.close();
041      }
042    }
043  }
044
045  private static final Map<Integer, DataStore> m_handleMap = new HashMap<>();
046  private static final Object m_handleLock = new Object();
047
048  private static DataStore getForModule(int module) {
049    synchronized (m_handleLock) {
050      Integer moduleBoxed = module;
051      DataStore pcm = m_handleMap.get(moduleBoxed);
052      if (pcm == null) {
053        pcm = new DataStore(module);
054      }
055      pcm.addRef();
056      return pcm;
057    }
058  }
059
060  private static void freeModule(DataStore store) {
061    synchronized (m_handleLock) {
062      store.removeRef();
063    }
064  }
065
066  private final DataStore m_dataStore;
067  private final int m_handle;
068
069  /** Constructs a PneumaticsControlModule with the default id (0). */
070  public PneumaticsControlModule() {
071    this(SensorUtil.getDefaultCTREPCMModule());
072  }
073
074  /**
075   * Constructs a PneumaticsControlModule.
076   *
077   * @param module module number to construct
078   */
079  public PneumaticsControlModule(int module) {
080    m_dataStore = getForModule(module);
081    m_handle = m_dataStore.m_handle;
082  }
083
084  @Override
085  public void close() {
086    freeModule(m_dataStore);
087  }
088
089  @Override
090  public boolean getCompressor() {
091    return CTREPCMJNI.getCompressor(m_handle);
092  }
093
094  @Override
095  public boolean getPressureSwitch() {
096    return CTREPCMJNI.getPressureSwitch(m_handle);
097  }
098
099  @Override
100  public double getCompressorCurrent() {
101    return CTREPCMJNI.getCompressorCurrent(m_handle);
102  }
103
104  public boolean getCompressorCurrentTooHighFault() {
105    return CTREPCMJNI.getCompressorCurrentTooHighFault(m_handle);
106  }
107
108  public boolean getCompressorCurrentTooHighStickyFault() {
109    return CTREPCMJNI.getCompressorCurrentTooHighStickyFault(m_handle);
110  }
111
112  public boolean getCompressorShortedFault() {
113    return CTREPCMJNI.getCompressorShortedFault(m_handle);
114  }
115
116  public boolean getCompressorShortedStickyFault() {
117    return CTREPCMJNI.getCompressorShortedStickyFault(m_handle);
118  }
119
120  public boolean getCompressorNotConnectedFault() {
121    return CTREPCMJNI.getCompressorNotConnectedFault(m_handle);
122  }
123
124  public boolean getCompressorNotConnectedStickyFault() {
125    return CTREPCMJNI.getCompressorNotConnectedStickyFault(m_handle);
126  }
127
128  @Override
129  public void setSolenoids(int mask, int values) {
130    CTREPCMJNI.setSolenoids(m_handle, mask, values);
131  }
132
133  @Override
134  public int getSolenoids() {
135    return CTREPCMJNI.getSolenoids(m_handle);
136  }
137
138  @Override
139  public int getModuleNumber() {
140    return m_dataStore.m_module;
141  }
142
143  @Override
144  public int getSolenoidDisabledList() {
145    return CTREPCMJNI.getSolenoidDisabledList(m_handle);
146  }
147
148  public boolean getSolenoidVoltageFault() {
149    return CTREPCMJNI.getSolenoidVoltageFault(m_handle);
150  }
151
152  public boolean getSolenoidVoltageStickyFault() {
153    return CTREPCMJNI.getSolenoidVoltageStickyFault(m_handle);
154  }
155
156  public void clearAllStickyFaults() {
157    CTREPCMJNI.clearAllStickyFaults(m_handle);
158  }
159
160  @Override
161  public void fireOneShot(int index) {
162    CTREPCMJNI.fireOneShot(m_handle, index);
163  }
164
165  @Override
166  public void setOneShotDuration(int index, int durMs) {
167    CTREPCMJNI.setOneShotDuration(m_handle, index, durMs);
168  }
169
170  @Override
171  public boolean checkSolenoidChannel(int channel) {
172    return CTREPCMJNI.checkSolenoidChannel(channel);
173  }
174
175  @Override
176  public int checkAndReserveSolenoids(int mask) {
177    synchronized (m_dataStore.m_reserveLock) {
178      if ((m_dataStore.m_reservedMask & mask) != 0) {
179        return m_dataStore.m_reservedMask & mask;
180      }
181      m_dataStore.m_reservedMask |= mask;
182      return 0;
183    }
184  }
185
186  @Override
187  public void unreserveSolenoids(int mask) {
188    synchronized (m_dataStore.m_reserveLock) {
189      m_dataStore.m_reservedMask &= ~mask;
190    }
191  }
192
193  @Override
194  public Solenoid makeSolenoid(int channel) {
195    return new Solenoid(m_dataStore.m_module, PneumaticsModuleType.CTREPCM, channel);
196  }
197
198  @Override
199  public DoubleSolenoid makeDoubleSolenoid(int forwardChannel, int reverseChannel) {
200    return new DoubleSolenoid(
201        m_dataStore.m_module, PneumaticsModuleType.CTREPCM, forwardChannel, reverseChannel);
202  }
203
204  @Override
205  public Compressor makeCompressor() {
206    return new Compressor(m_dataStore.m_module, PneumaticsModuleType.CTREPCM);
207  }
208
209  @Override
210  public boolean reserveCompressor() {
211    synchronized (m_dataStore.m_reserveLock) {
212      if (m_dataStore.m_compressorReserved) {
213        return false;
214      }
215      m_dataStore.m_compressorReserved = true;
216      return true;
217    }
218  }
219
220  @Override
221  public void unreserveCompressor() {
222    synchronized (m_dataStore.m_reserveLock) {
223      m_dataStore.m_compressorReserved = false;
224    }
225  }
226
227  @Override
228  public void disableCompressor() {
229    CTREPCMJNI.setClosedLoopControl(m_handle, false);
230  }
231
232  @Override
233  public void enableCompressorDigital() {
234    CTREPCMJNI.setClosedLoopControl(m_handle, true);
235  }
236
237  @Override
238  public void enableCompressorAnalog(double minPressure, double maxPressure) {
239    CTREPCMJNI.setClosedLoopControl(m_handle, false);
240  }
241
242  @Override
243  public void enableCompressorHybrid(double minPressure, double maxPressure) {
244    CTREPCMJNI.setClosedLoopControl(m_handle, false);
245  }
246
247  @Override
248  public CompressorConfigType getCompressorConfigType() {
249    return CTREPCMJNI.getClosedLoopControl(m_handle)
250        ? CompressorConfigType.Digital
251        : CompressorConfigType.Disabled;
252  }
253
254  @Override
255  public double getAnalogVoltage(int channel) {
256    return 0;
257  }
258
259  @Override
260  public double getPressure(int channel) {
261    return 0;
262  }
263}