Class Compressor
- java.lang.Object
-
- edu.wpi.first.wpilibj.SendableBase
-
- edu.wpi.first.wpilibj.Compressor
-
- All Implemented Interfaces:
Sendable
,AutoCloseable
public class Compressor extends SendableBase
Class for operating a compressor connected to a PCM (Pneumatic Control Module). The PCM will automatically run in closed loop mode by default whenever aSolenoid
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 Summary
Constructors Constructor Description Compressor()
Makes a new instance of the compressor using the default PCM ID of 0.Compressor(int module)
Makes a new instance of the compressor using the provided CAN device ID.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
clearAllPCMStickyFaults()
Clear ALL sticky faults inside PCM that Compressor is wired to.boolean
enabled()
Get the status of the compressor.boolean
getClosedLoopControl()
Gets the current operating mode of the PCM.double
getCompressorCurrent()
Get the current being used by the compressor.boolean
getCompressorCurrentTooHighFault()
If PCM is in fault state : Compressor Drive is disabled due to compressor current being too high.boolean
getCompressorCurrentTooHighStickyFault()
If PCM sticky fault is set : Compressor is disabled due to compressor current being too high.boolean
getCompressorNotConnectedFault()
If PCM is in fault state : Compressor does not appear to be wired, i.e.boolean
getCompressorNotConnectedStickyFault()
If PCM sticky fault is set : Compressor does not appear to be wired, i.e.boolean
getCompressorShortedFault()
If PCM is in fault state : Compressor output appears to be shorted.boolean
getCompressorShortedStickyFault()
If PCM sticky fault is set : Compressor output appears to be shorted.boolean
getPressureSwitchValue()
Get the pressure switch value.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.void
setClosedLoopControl(boolean on)
Set the PCM in closed loop control mode.void
start()
Start the compressor running in closed loop control mode.void
stop()
Stop the compressor from running in closed loop control mode.-
Methods inherited from class edu.wpi.first.wpilibj.SendableBase
addChild, close, free, getName, getSubsystem, setName, setName, setName, setSubsystem
-
-
-
-
Constructor Detail
-
Compressor
public Compressor(int module)
Makes a new instance of the compressor using the provided CAN device ID. Use this constructor when you have more than one PCM.- Parameters:
module
- The PCM CAN device ID (0 - 62 inclusive)
-
Compressor
public Compressor()
Makes a new instance of the compressor using the default PCM ID of 0.Additional modules can be supported by making a new instance and
specifying the CAN ID.
-
-
Method Detail
-
start
public void start()
Start the compressor running in closed loop control mode.Use the method in cases where you would like to manually stop and start the compressor for applications such as conserving battery or making sure that the compressor motor doesn't start during critical operations.
-
stop
public void stop()
Stop the compressor from running in closed loop control mode.Use the method in cases where you would like to manually stop and start the compressor for applications such as conserving battery or making sure that the compressor motor doesn't start during critical operations.
-
enabled
public boolean enabled()
Get the status of the compressor.- Returns:
- true if the compressor is on
-
getPressureSwitchValue
public boolean getPressureSwitchValue()
Get the pressure switch value.- Returns:
- true if the pressure is low
-
getCompressorCurrent
public double getCompressorCurrent()
Get the current being used by the compressor.- Returns:
- current consumed by the compressor in amps
-
setClosedLoopControl
public void setClosedLoopControl(boolean on)
Set the PCM in closed loop control mode.- Parameters:
on
- if true sets the compressor to be in closed loop control mode (default)
-
getClosedLoopControl
public boolean getClosedLoopControl()
Gets the current operating mode of the PCM.- Returns:
- true if compressor is operating on closed-loop mode
-
getCompressorCurrentTooHighFault
public boolean getCompressorCurrentTooHighFault()
If PCM is in fault state : Compressor Drive is disabled due to compressor current being too high.- Returns:
- true if PCM is in fault state.
-
getCompressorCurrentTooHighStickyFault
public boolean getCompressorCurrentTooHighStickyFault()
If PCM sticky fault is set : Compressor is disabled due to compressor current being too high.- Returns:
- true if PCM sticky fault is set.
-
getCompressorShortedStickyFault
public boolean getCompressorShortedStickyFault()
If PCM sticky fault is set : Compressor output appears to be shorted.- Returns:
- true if PCM sticky fault is set.
-
getCompressorShortedFault
public boolean getCompressorShortedFault()
If PCM is in fault state : Compressor output appears to be shorted.- Returns:
- true if PCM is in fault state.
-
getCompressorNotConnectedStickyFault
public boolean getCompressorNotConnectedStickyFault()
If PCM sticky fault is set : Compressor does not appear to be wired, i.e. compressor is not drawing enough current.- Returns:
- true if PCM sticky fault is set.
-
getCompressorNotConnectedFault
public boolean getCompressorNotConnectedFault()
If PCM is in fault state : Compressor does not appear to be wired, i.e. compressor is not drawing enough current.- Returns:
- true if PCM is in fault state.
-
clearAllPCMStickyFaults
public void clearAllPCMStickyFaults()
Clear ALL sticky faults inside PCM that Compressor is wired to.If a sticky fault is set, then it will be persistently cleared. The compressor might momentarily disable while the flags are being cleared. Doo not call this method too frequently, otherwise normal compressor functionality may be prevented.
If no sticky faults are set then this call will have no effect.
-
initSendable
public void initSendable(SendableBuilder builder)
Description copied from interface:Sendable
Initializes thisSendable
object.- Parameters:
builder
- sendable builder
-
-