|
| 1 | +#!/usr/bin/env python3 |
| 2 | + |
| 3 | +import wpilib |
| 4 | +from wpilib.shuffleboard import Shuffleboard |
| 5 | + |
| 6 | +""" |
| 7 | +This is a sample program showing the use of the solenoid classes during operator control. Three |
| 8 | +buttons from a joystick will be used to control two solenoids: One button to control the position |
| 9 | +of a single solenoid and the other two buttons to control a double solenoid. Single solenoids can |
| 10 | +either be on or off, such that the air diverted through them goes through either one channel or |
| 11 | +the other. Double solenoids have three states: Off, Forward, and Reverse. Forward and Reverse |
| 12 | +divert the air through the two channels and correspond to the on and off of a single solenoid, |
| 13 | +but a double solenoid can also be "off", where the solenoid will remain in its default power off |
| 14 | +state. Additionally, double solenoids take up two channels on your PCM whereas single solenoids |
| 15 | +only take a single channel. |
| 16 | +""" |
| 17 | + |
| 18 | + |
| 19 | +class MyRobot(wpilib.TimedRobot): |
| 20 | + def robotInit(self): |
| 21 | + self.joystick = wpilib.Joystick(0) |
| 22 | + |
| 23 | + # Solenoid corresponds to a single solenoid. |
| 24 | + # In this case, it's connected to channel 0 of a PH with the default CAN ID. |
| 25 | + self.solenoid = wpilib.Solenoid( |
| 26 | + moduleType=wpilib.PneumaticsModuleType.REVPH, channel=0 |
| 27 | + ) |
| 28 | + |
| 29 | + # DoubleSolenoid corresponds to a double solenoid. |
| 30 | + # In this case, it's connected to channels 1 and 2 of a PH with the default CAN ID. |
| 31 | + self.doubleSolenoid = wpilib.DoubleSolenoid( |
| 32 | + moduleType=wpilib.PneumaticsModuleType.REVPH, |
| 33 | + forwardChannel=1, |
| 34 | + reverseChannel=2, |
| 35 | + ) |
| 36 | + |
| 37 | + # Compressor connected to a PH with a default CAN ID (1) |
| 38 | + self.compressor = wpilib.Compressor(wpilib.PneumaticsModuleType.REVPH) |
| 39 | + |
| 40 | + self.kSolenoidButton = 1 |
| 41 | + self.kDoubleSolenoidForwardButton = 2 |
| 42 | + self.kDoubleSolenoidReverseButton = 3 |
| 43 | + self.kCompressorButton = 4 |
| 44 | + |
| 45 | + # |
| 46 | + # Publish elements to shuffleboard |
| 47 | + # |
| 48 | + |
| 49 | + tab = Shuffleboard.getTab("Pneumatics") |
| 50 | + tab.add("Single Solenoid", self.solenoid) |
| 51 | + tab.add("Double Solenoid", self.doubleSolenoid) |
| 52 | + tab.add("Compressor", self.compressor) |
| 53 | + |
| 54 | + # Also publish some raw data |
| 55 | + tab.addDouble("PH Pressure [PSI]", lambda: self.compressor.getCurrent()) |
| 56 | + tab.addDouble("Compressor Current [A]", lambda: self.compressor.getCurrent()) |
| 57 | + tab.addBoolean("Compressor Active", lambda: self.compressor.isEnabled()) |
| 58 | + tab.addBoolean( |
| 59 | + "Pressure Switch", lambda: self.compressor.getPressureSwitchValue() |
| 60 | + ) |
| 61 | + |
| 62 | + def teleopPeriodic(self): |
| 63 | + # The output of GetRawButton is true/false depending on whether |
| 64 | + # the button is pressed; Set takes a boolean for whether |
| 65 | + # to retract the solenoid (false) or extend it (true). |
| 66 | + self.solenoid.set(self.joystick.getRawButton(self.kSolenoidButton)) |
| 67 | + |
| 68 | + # GetRawButtonPressed will only return true once per press. |
| 69 | + # If a button is pressed, set the solenoid to the respective channel. |
| 70 | + |
| 71 | + if self.joystick.getRawButtonPressed(self.kDoubleSolenoidForwardButton): |
| 72 | + self.doubleSolenoid.set(wpilib.DoubleSolenoid.Value.kForward) |
| 73 | + elif self.joystick.getRawButtonPressed(self.kDoubleSolenoidReverseButton): |
| 74 | + self.doubleSolenoid.set(wpilib.DoubleSolenoid.Value.kReverse) |
| 75 | + |
| 76 | + # On button press, toggle the compressor. |
| 77 | + if self.joystick.getRawButtonPressed(self.kCompressorButton): |
| 78 | + # Check whether the compressor is currently enabled. |
| 79 | + isCompressorEnabled = self.compressor.isEnabled() |
| 80 | + if isCompressorEnabled: |
| 81 | + # Disable closed-loop mode on the compressor |
| 82 | + self.compressor.disable() |
| 83 | + else: |
| 84 | + # Change the if states to select the closed-loop you want to use: |
| 85 | + |
| 86 | + if False: |
| 87 | + # Enable the closed-lopp mode base on the digital pressure switch connect to the PCM/PH. |
| 88 | + # The switch is open when the pressure is over ~120 PSI. |
| 89 | + self.compressor.enableDigital() |
| 90 | + |
| 91 | + if True: |
| 92 | + # Enable closed-loop mode based on the analog pressure sensor connected to the PH. |
| 93 | + # The compressor will run while the pressure reported by the sensor is in the |
| 94 | + # specified range ([70 PSI, 120 PSI] in this example). |
| 95 | + # Analog mode exists only on the PH! On the PCM, this enables digital control. |
| 96 | + self.compressor.enableAnalog(70, 120) |
| 97 | + |
| 98 | + if False: |
| 99 | + # Enable closed-loop mode based on both the digital pressure switch AND the analog |
| 100 | + # pressure sensor connected to the PH. |
| 101 | + # The compressor will run while the pressure reported by the analog sensor is in the |
| 102 | + # specified range ([70 PSI, 120 PSI] in this example) AND the digital switch reports |
| 103 | + # that the system is not full. |
| 104 | + # Hybrid mode exists only on the PH! On the PCM, this enables digital control. |
| 105 | + self.compressor.enableHybrid(70, 120) |
| 106 | + |
| 107 | + |
| 108 | +if __name__ == "__main__": |
| 109 | + wpilib.run(MyRobot) |
0 commit comments