mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[examples] Improve Pneumatics example coverage in Solenoid and RapidReactCmdBot examples (#4998)
This commit is contained in:
@@ -68,6 +68,7 @@
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Joystick",
|
||||
"Shuffleboard",
|
||||
"Pneumatics"
|
||||
],
|
||||
"foldername": "solenoid",
|
||||
|
||||
@@ -63,7 +63,7 @@ public final class Constants {
|
||||
|
||||
public static final class IntakeConstants {
|
||||
public static final int kMotorPort = 6;
|
||||
public static final int[] kSolenoidPorts = {0, 1};
|
||||
public static final int[] kSolenoidPorts = {2, 3};
|
||||
}
|
||||
|
||||
public static final class StorageConstants {
|
||||
|
||||
@@ -11,6 +11,7 @@ import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.OIConstants
|
||||
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.ShooterConstants;
|
||||
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Drive;
|
||||
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Intake;
|
||||
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Pneumatics;
|
||||
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Shooter;
|
||||
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Storage;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
@@ -29,6 +30,7 @@ public class RapidReactCommandBot {
|
||||
private final Intake m_intake = new Intake();
|
||||
private final Storage m_storage = new Storage();
|
||||
private final Shooter m_shooter = new Shooter();
|
||||
private final Pneumatics m_pneumatics = new Pneumatics();
|
||||
|
||||
// The driver's controller
|
||||
CommandXboxController m_driverController =
|
||||
@@ -69,6 +71,9 @@ public class RapidReactCommandBot {
|
||||
m_storage.runCommand())
|
||||
// Since we composed this inline we should give it a name
|
||||
.withName("Shoot"));
|
||||
|
||||
// Toggle compressor with the Start button
|
||||
m_driverController.start().toggleOnTrue(m_pneumatics.disableCompressorCommand());
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -14,9 +14,11 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Intake extends SubsystemBase {
|
||||
private final PWMSparkMax m_motor = new PWMSparkMax(IntakeConstants.kMotorPort);
|
||||
|
||||
// Double solenoid connected to two channels of a PCM with the default CAN ID
|
||||
private final DoubleSolenoid m_pistons =
|
||||
new DoubleSolenoid(
|
||||
PneumaticsModuleType.REVPH,
|
||||
PneumaticsModuleType.CTREPCM,
|
||||
IntakeConstants.kSolenoidPorts[0],
|
||||
IntakeConstants.kSolenoidPorts[1]);
|
||||
|
||||
|
||||
@@ -0,0 +1,65 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj.AnalogPotentiometer;
|
||||
import edu.wpi.first.wpilibj.Compressor;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/** Subsystem for managing the compressor, pressure sensor, etc. */
|
||||
public class Pneumatics extends SubsystemBase {
|
||||
// External analog pressure sensor
|
||||
// product-specific voltage->pressure conversion, see product manual
|
||||
// in this case, 250(V/5)-25
|
||||
// the scale parameter in the AnalogPotentiometer constructor is scaled from 1 instead of 5,
|
||||
// so if r is the raw AnalogPotentiometer output, the pressure is 250r-25
|
||||
static final double kScale = 250;
|
||||
static final double kOffset = -25;
|
||||
private final AnalogPotentiometer m_pressureTransducer =
|
||||
new AnalogPotentiometer(/* the AnalogIn port*/ 2, kScale, kOffset);
|
||||
|
||||
// Compressor connected to a PCM with a default CAN ID (0)
|
||||
private final Compressor m_compressor = new Compressor(PneumaticsModuleType.CTREPCM);
|
||||
|
||||
public Pneumatics() {
|
||||
var tab = Shuffleboard.getTab("Pneumatics");
|
||||
tab.addDouble("External Pressure [PSI]", this::getPressure);
|
||||
}
|
||||
|
||||
/**
|
||||
* Query the analog pressure sensor.
|
||||
*
|
||||
* @return the measured pressure, in PSI
|
||||
*/
|
||||
private double getPressure() {
|
||||
// Get the pressure (in PSI) from an analog pressure sensor connected to the RIO.
|
||||
return m_pressureTransducer.get();
|
||||
}
|
||||
|
||||
/**
|
||||
* Disable the compressor closed-loop for as long as the command runs.
|
||||
*
|
||||
* <p>Structured this way as the compressor is enabled by default.
|
||||
*
|
||||
* @return command
|
||||
*/
|
||||
public CommandBase disableCompressorCommand() {
|
||||
return startEnd(
|
||||
() -> {
|
||||
// Disable closed-loop mode on the compressor.
|
||||
m_compressor.disable();
|
||||
},
|
||||
() -> {
|
||||
// Enable closed-loop mode based on the digital pressure switch connected to the
|
||||
// PCM/PH.
|
||||
// The switch is open when the pressure is over ~120 PSI.
|
||||
m_compressor.enableDigital();
|
||||
})
|
||||
.withName("Compressor Disabled");
|
||||
}
|
||||
}
|
||||
@@ -4,11 +4,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.solenoid;
|
||||
|
||||
import edu.wpi.first.wpilibj.Compressor;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.Solenoid;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
|
||||
/**
|
||||
* This is a sample program showing the use of the solenoid classes during operator control. Three
|
||||
@@ -25,34 +28,111 @@ public class Robot extends TimedRobot {
|
||||
private final Joystick m_stick = new Joystick(0);
|
||||
|
||||
// Solenoid corresponds to a single solenoid.
|
||||
private final Solenoid m_solenoid = new Solenoid(PneumaticsModuleType.CTREPCM, 0);
|
||||
// In this case, it's connected to channel 0 of a PH with the default CAN ID.
|
||||
private final Solenoid m_solenoid = new Solenoid(PneumaticsModuleType.REVPH, 0);
|
||||
|
||||
// DoubleSolenoid corresponds to a double solenoid.
|
||||
// In this case, it's connected to channels 1 and 2 of a PH with the default CAN ID.
|
||||
private final DoubleSolenoid m_doubleSolenoid =
|
||||
new DoubleSolenoid(PneumaticsModuleType.CTREPCM, 1, 2);
|
||||
new DoubleSolenoid(PneumaticsModuleType.REVPH, 1, 2);
|
||||
|
||||
private static final int kSolenoidButton = 1;
|
||||
private static final int kDoubleSolenoidForward = 2;
|
||||
private static final int kDoubleSolenoidReverse = 3;
|
||||
// Compressor connected to a PH with a default CAN ID (1)
|
||||
private final Compressor m_compressor = new Compressor(PneumaticsModuleType.REVPH);
|
||||
|
||||
static final int kSolenoidButton = 1;
|
||||
static final int kDoubleSolenoidForwardButton = 2;
|
||||
static final int kDoubleSolenoidReverseButton = 3;
|
||||
static final int kCompressorButton = 4;
|
||||
|
||||
@Override
|
||||
public void robotInit() {
|
||||
// Publish elements to shuffleboard.
|
||||
ShuffleboardTab tab = Shuffleboard.getTab("Pneumatics");
|
||||
tab.add("Single Solenoid", m_solenoid);
|
||||
tab.add("Double Solenoid", m_doubleSolenoid);
|
||||
tab.add("Compressor", m_compressor);
|
||||
|
||||
// Also publish some raw data
|
||||
tab.addDouble(
|
||||
"PH Pressure [PSI]",
|
||||
() -> {
|
||||
// Get the pressure (in PSI) from the analog sensor connected to the PH.
|
||||
// This function is supported only on the PH!
|
||||
// On a PCM, this function will return 0.
|
||||
return m_compressor.getPressure();
|
||||
});
|
||||
tab.addDouble(
|
||||
"Compressor Current",
|
||||
() -> {
|
||||
// Get compressor current draw.
|
||||
return m_compressor.getCurrent();
|
||||
});
|
||||
tab.addBoolean(
|
||||
"Compressor Active",
|
||||
() -> {
|
||||
// Get whether the compressor is active.
|
||||
return m_compressor.isEnabled();
|
||||
});
|
||||
tab.addBoolean(
|
||||
"Pressure Switch",
|
||||
() -> {
|
||||
// Get the digital pressure switch connected to the PCM/PH.
|
||||
// The switch is open when the pressure is over ~120 PSI.
|
||||
return m_compressor.getPressureSwitchValue();
|
||||
});
|
||||
}
|
||||
|
||||
@SuppressWarnings("PMD.UnconditionalIfStatement")
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
/*
|
||||
* The output of GetRawButton is true/false depending on whether
|
||||
* the button is pressed; Set takes a boolean for whether
|
||||
* to use the default (false) channel or the other (true).
|
||||
* to retract the solenoid (false) or extend it (true).
|
||||
*/
|
||||
m_solenoid.set(m_stick.getRawButton(kSolenoidButton));
|
||||
|
||||
/*
|
||||
* In order to set the double solenoid, if just one button
|
||||
* is pressed, set the solenoid to correspond to that button.
|
||||
* If both are pressed, set the solenoid will be set to Forwards.
|
||||
* GetRawButtonPressed will only return true once per press.
|
||||
* If a button is pressed, set the solenoid to the respective channel.
|
||||
*/
|
||||
if (m_stick.getRawButton(kDoubleSolenoidForward)) {
|
||||
if (m_stick.getRawButtonPressed(kDoubleSolenoidForwardButton)) {
|
||||
m_doubleSolenoid.set(DoubleSolenoid.Value.kForward);
|
||||
} else if (m_stick.getRawButton(kDoubleSolenoidReverse)) {
|
||||
} else if (m_stick.getRawButtonPressed(kDoubleSolenoidReverseButton)) {
|
||||
m_doubleSolenoid.set(DoubleSolenoid.Value.kReverse);
|
||||
}
|
||||
|
||||
// On button press, toggle the compressor.
|
||||
if (m_stick.getRawButtonPressed(kCompressorButton)) {
|
||||
// Check whether the compressor is currently enabled.
|
||||
boolean isCompressorEnabled = m_compressor.isEnabled();
|
||||
if (isCompressorEnabled) {
|
||||
// Disable closed-loop mode on the compressor.
|
||||
m_compressor.disable();
|
||||
} else {
|
||||
// Change the if statements to select the closed-loop you want to use:
|
||||
if (false) {
|
||||
// Enable closed-loop mode based on the digital pressure switch connected to the PCM/PH.
|
||||
// The switch is open when the pressure is over ~120 PSI.
|
||||
m_compressor.enableDigital();
|
||||
}
|
||||
if (true) {
|
||||
// Enable closed-loop mode based on the analog pressure sensor connected to the PH.
|
||||
// The compressor will run while the pressure reported by the sensor is in the
|
||||
// specified range ([70 PSI, 120 PSI] in this example).
|
||||
// Analog mode exists only on the PH! On the PCM, this enables digital control.
|
||||
m_compressor.enableAnalog(70, 120);
|
||||
}
|
||||
if (false) {
|
||||
// Enable closed-loop mode based on both the digital pressure switch AND the analog
|
||||
// pressure sensor connected to the PH.
|
||||
// The compressor will run while the pressure reported by the analog sensor is in the
|
||||
// specified range ([70 PSI, 120 PSI] in this example) AND the digital switch reports
|
||||
// that the system is not full.
|
||||
// Hybrid mode exists only on the PH! On the PCM, this enables digital control.
|
||||
m_compressor.enableHybrid(70, 120);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user