Class Compressor

java.lang.Object
edu.wpi.first.wpilibj.Compressor
All Implemented Interfaces:
Sendable, AutoCloseable

public class Compressor
extends Object
implements Sendable, AutoCloseable
Class for operating a compressor connected to a pneumatics module. The module will automatically run in closed loop mode by default whenever a Solenoid object is created. For most cases, a Compressor object does not need to be instantiated or used in a robot program. This class is only required in cases where the robot program needs a more detailed status of the compressor or to enable/disable closed loop control.

Note: you cannot operate the compressor directly from this class as doing so would circumvent the safety provided by using the pressure switch and closed loop control. You can only turn off closed loop control, thereby stopping the compressor from operating.

  • Constructor Details

  • Method Details

    • close

      public void close()
      Specified by:
      close in interface AutoCloseable
    • enabled

      @Deprecated(since="2023", forRemoval=true) public boolean enabled()
      Deprecated, for removal: This API element is subject to removal in a future version.
      To avoid confusion in thinking this (re)enables the compressor use IsEnabled().
      Get the status of the compressor. To (re)enable the compressor use enableDigital() or enableAnalog(...).
      Returns:
      true if the compressor is on
    • isEnabled

      public boolean isEnabled()
      Returns whether the compressor is active or not.
      Returns:
      true if the compressor is on - otherwise false.
    • getPressureSwitchValue

      public boolean getPressureSwitchValue()
      Get the pressure switch value.
      Returns:
      true if the pressure is low
    • getCurrent

      public double getCurrent()
      Get the current being used by the compressor.
      Returns:
      current consumed by the compressor in amps
    • getAnalogVoltage

      public double getAnalogVoltage()
      Query the analog input voltage (on channel 0) (if supported).
      Returns:
      The analog input voltage, in volts
    • getPressure

      public double getPressure()
      Query the analog sensor pressure (on channel 0) (if supported). Note this is only for use with the REV Analog Pressure Sensor.
      Returns:
      The analog sensor pressure, in PSI
    • disable

      public void disable()
      Disable the compressor.
    • enableDigital

      public void enableDigital()
      Enable compressor closed loop control using digital input.
    • enableAnalog

      public void enableAnalog​(double minPressure, double maxPressure)
      Enable compressor closed loop control using analog input. Note this is only for use with the REV Analog Pressure Sensor.

      On CTRE PCM, this will enable digital control.

      Parameters:
      minPressure - The minimum pressure in PSI to enable compressor
      maxPressure - The maximum pressure in PSI to disable compressor
    • enableHybrid

      public void enableHybrid​(double minPressure, double maxPressure)
      Enable compressor closed loop control using hybrid input. Note this is only for use with the REV Analog Pressure Sensor.

      On CTRE PCM, this will enable digital control.

      Parameters:
      minPressure - The minimum pressure in PSI to enable compressor
      maxPressure - The maximum pressure in PSI to disable compressor
    • getConfigType

      Gets the current operating mode of the Compressor.
      Returns:
      true if compressor is operating on closed-loop mode
    • initSendable

      public void initSendable​(SendableBuilder builder)
      Description copied from interface: Sendable
      Initializes this Sendable object.
      Specified by:
      initSendable in interface Sendable
      Parameters:
      builder - sendable builder