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.FRCNetComm.tResourceType;
008import edu.wpi.first.hal.HAL;
009import edu.wpi.first.hal.util.AllocationException;
010import edu.wpi.first.util.sendable.Sendable;
011import edu.wpi.first.util.sendable.SendableBuilder;
012import edu.wpi.first.util.sendable.SendableRegistry;
013
014/**
015 * Class for operating a compressor connected to a pneumatics module. The module will automatically
016 * run in closed loop mode by default whenever a {@link Solenoid} object is created. For most cases,
017 * a Compressor object does not need to be instantiated or used in a robot program. This class is
018 * only required in cases where the robot program needs a more detailed status of the compressor or
019 * to enable/disable closed loop control.
020 *
021 * <p>Note: you cannot operate the compressor directly from this class as doing so would circumvent
022 * the safety provided by using the pressure switch and closed loop control. You can only turn off
023 * closed loop control, thereby stopping the compressor from operating.
024 */
025public class Compressor implements Sendable, AutoCloseable {
026  private PneumaticsBase m_module;
027
028  /**
029   * Constructs a compressor for a specified module and type.
030   *
031   * @param module The module ID to use.
032   * @param moduleType The module type to use.
033   */
034  public Compressor(int module, PneumaticsModuleType moduleType) {
035    m_module = PneumaticsBase.getForType(module, moduleType);
036
037    if (!m_module.reserveCompressor()) {
038      m_module.close();
039      throw new AllocationException("Compressor already allocated");
040    }
041
042    m_module.enableCompressorDigital();
043
044    HAL.report(tResourceType.kResourceType_Compressor, module + 1);
045    SendableRegistry.addLW(this, "Compressor", module);
046  }
047
048  /**
049   * Constructs a compressor for a default module and specified type.
050   *
051   * @param moduleType The module type to use.
052   */
053  public Compressor(PneumaticsModuleType moduleType) {
054    this(PneumaticsBase.getDefaultForType(moduleType), moduleType);
055  }
056
057  @Override
058  public void close() {
059    SendableRegistry.remove(this);
060    m_module.unreserveCompressor();
061    m_module.close();
062    m_module = null;
063  }
064
065  /**
066   * Start the compressor running in closed loop control mode.
067   *
068   * <p>Use the method in cases where you would like to manually stop and start the compressor for
069   * applications such as conserving battery or making sure that the compressor motor doesn't start
070   * during critical operations.
071   *
072   * @deprecated Use enableDigital() instead.
073   */
074  @Deprecated(since = "2022", forRemoval = true)
075  public void start() {
076    enableDigital();
077  }
078
079  /**
080   * Stop the compressor from running in closed loop control mode.
081   *
082   * <p>Use the method in cases where you would like to manually stop and start the compressor for
083   * applications such as conserving battery or making sure that the compressor motor doesn't start
084   * during critical operations.
085   *
086   * @deprecated Use disable() instead.
087   */
088  @Deprecated(since = "2022", forRemoval = true)
089  public void stop() {
090    disable();
091  }
092
093  /**
094   * Get the status of the compressor.
095   *
096   * @return true if the compressor is on
097   */
098  public boolean enabled() {
099    return m_module.getCompressor();
100  }
101
102  /**
103   * Get the pressure switch value.
104   *
105   * @return true if the pressure is low
106   */
107  public boolean getPressureSwitchValue() {
108    return m_module.getPressureSwitch();
109  }
110
111  /**
112   * Get the current being used by the compressor.
113   *
114   * @return current consumed by the compressor in amps
115   */
116  public double getCurrent() {
117    return m_module.getCompressorCurrent();
118  }
119
120  /**
121   * Query the analog input voltage (on channel 0) (if supported).
122   *
123   * @return The analog input voltage, in volts
124   */
125  public double getAnalogVoltage() {
126    return m_module.getAnalogVoltage(0);
127  }
128
129  /**
130   * Query the analog sensor pressure (on channel 0) (if supported). Note this is only for use with
131   * the REV Analog Pressure Sensor.
132   *
133   * @return The analog sensor pressure, in PSI
134   */
135  public double getPressure() {
136    return m_module.getPressure(0);
137  }
138
139  /** Disable the compressor. */
140  public void disable() {
141    m_module.disableCompressor();
142  }
143
144  /** Enable compressor closed loop control using digital input. */
145  public void enableDigital() {
146    m_module.enableCompressorDigital();
147  }
148
149  /**
150   * Enable compressor closed loop control using analog input. Note this is only for use with the
151   * REV Analog Pressure Sensor.
152   *
153   * <p>On CTRE PCM, this will enable digital control.
154   *
155   * @param minPressure The minimum pressure in PSI to enable compressor
156   * @param maxPressure The maximum pressure in PSI to disable compressor
157   */
158  public void enableAnalog(double minPressure, double maxPressure) {
159    m_module.enableCompressorAnalog(minPressure, maxPressure);
160  }
161
162  /**
163   * Enable compressor closed loop control using hybrid input. Note this is only for use with the
164   * REV Analog Pressure Sensor.
165   *
166   * <p>On CTRE PCM, this will enable digital control.
167   *
168   * @param minPressure The minimum pressure in PSI to enable compressor
169   * @param maxPressure The maximum pressure in PSI to disable compressor
170   */
171  public void enableHybrid(double minPressure, double maxPressure) {
172    m_module.enableCompressorHybrid(minPressure, maxPressure);
173  }
174
175  /**
176   * Gets the current operating mode of the Compressor.
177   *
178   * @return true if compressor is operating on closed-loop mode
179   */
180  public CompressorConfigType getConfigType() {
181    return m_module.getCompressorConfigType();
182  }
183
184  @Override
185  public void initSendable(SendableBuilder builder) {
186    builder.setSmartDashboardType("Compressor");
187    builder.addBooleanProperty("Enabled", this::enabled, null);
188    builder.addBooleanProperty("Pressure switch", this::getPressureSwitchValue, null);
189  }
190}