Skip to content

Commit ba6a18d

Browse files
committed
hopper stuff
1 parent ccf1ab9 commit ba6a18d

File tree

5 files changed

+91
-5
lines changed

5 files changed

+91
-5
lines changed

src/main/java/frc/robot/Constants.java

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,11 @@ public static class ShooterConstants {
2424
public static final int HOODID = 9;
2525
}
2626

27+
public final class HopperConstants {
28+
29+
public static final int HOPPERID = 13;
30+
}
31+
2732
public static enum Mode {
2833
/** Running on a real robot. */
2934
REAL,

src/main/java/frc/robot/RobotContainer.java

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
1919
import frc.robot.commands.DriveCommands;
2020
import frc.robot.generated.TunerConstants;
21+
import frc.robot.subsystems.Hopper.Hopper;
2122
import frc.robot.subsystems.drive.Drive;
2223
import frc.robot.subsystems.drive.GyroIO;
2324
import frc.robot.subsystems.drive.GyroIONavX;
@@ -36,7 +37,7 @@
3637
public class RobotContainer {
3738
// Subsystems
3839
private final Drive drive;
39-
40+
private final Hopper hopper;
4041
// Controller
4142
private final CommandXboxController controller = new CommandXboxController(0);
4243

@@ -168,9 +169,12 @@ private void configureButtonBindings() {
168169
drive)
169170
.ignoringDisable(true));
170171

171-
controller.rightBumper().onFalse(m_Shooter.PIDCMD(500));
172-
controller.rightBumper().onTrue(m_Shooter.PIDCMD(0));
173-
}
172+
controller.leftBumper().onFalse(m_Shooter.PIDCMD(500));
173+
controller.leftBumper().onTrue(m_Shooter.PIDCMD(0));
174+
controller.rightBumper().onFalse(Commands.parallel(hopper.StopCMD(), m_Shooter.PIDCMD(0)));
175+
controller.rightBumper().onTrue(Commands.parallel(hopper.SpinCMD(), m_Shooter.PIDCMD(500)));
176+
177+
174178

175179
/**
176180
* Use this to pass the autonomous command to the main {@link Robot} class.
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
// Copyright (c) FIRST and other WPILib contributors.
2+
// Open Source Software; you can modify and/or share it under the terms of
3+
// the WPILib BSD license file in the root directory of this project.
4+
5+
package frc.robot.commands;
6+
7+
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
8+
import frc.robot.subsystems.Hopper.Hopper;
9+
import frc.robot.subsystems.shooter.Shooter;
10+
11+
// NOTE: Consider using this command inline, rather than writing a subclass. For more
12+
// information, see:
13+
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
14+
public class Shooter_Hopper extends ParallelCommandGroup {
15+
/** Creates a new Shooter_Hopper. */
16+
public Shooter_Hopper(Hopper mHopper, Shooter mShooter) {
17+
18+
// Add your commands in the addCommands() call, e.g.
19+
// addCommands(new FooCommand(), new BarCommand());
20+
addCommands(mHopper.SpinCMD(), mShooter.PIDCMD(0));
21+
}
22+
}
Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,53 @@
1+
// Copyright (c) FIRST and other WPILib contributors.
2+
// Open Source Software; you can modify and/or share it under the terms of
3+
// the WPILib BSD license file in the root directory of this project.
4+
5+
package frc.robot.subsystems.Hopper;
6+
7+
import com.revrobotics.PersistMode;
8+
import com.revrobotics.ResetMode;
9+
import com.revrobotics.spark.SparkLowLevel.MotorType;
10+
import com.revrobotics.spark.SparkMax;
11+
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
12+
import com.revrobotics.spark.config.SparkMaxConfig;
13+
import edu.wpi.first.wpilibj.DriverStation;
14+
import edu.wpi.first.wpilibj2.command.Command;
15+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
16+
import frc.robot.Constants;
17+
18+
public class Hopper extends SubsystemBase {
19+
/** Creates a new Hopper. */
20+
SparkMax Hopper = new SparkMax(Constants.HopperConstants.HOPPERID, MotorType.kBrushless);
21+
22+
public Hopper() {
23+
SparkMaxConfig config = new SparkMaxConfig();
24+
config.smartCurrentLimit(50).idleMode(IdleMode.kCoast);
25+
26+
// Persist parameters to retain configuration in the event of a power cycle
27+
Hopper.configure(config, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
28+
}
29+
30+
public Command SpinCMD() {
31+
32+
return runOnce(
33+
() -> {
34+
Hopper.set(1);
35+
DriverStation.reportWarning("StartHopper", false);
36+
});
37+
}
38+
39+
public Command StopCMD() {
40+
41+
return runOnce(
42+
() -> {
43+
Hopper.set(0);
44+
DriverStation.reportWarning("StopHopper", false);
45+
});
46+
}
47+
48+
@Override
49+
public void periodic() {
50+
// This method will be called once per scheduler run
51+
52+
}
53+
}

src/main/java/frc/robot/subsystems/shooter/Shooter.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
import com.revrobotics.spark.SparkMax;
1515
import com.revrobotics.spark.config.SparkMaxConfig;
1616
import edu.wpi.first.math.system.plant.DCMotor;
17+
import edu.wpi.first.wpilibj.DriverStation;
1718
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1819
import edu.wpi.first.wpilibj2.command.Command;
1920
import edu.wpi.first.wpilibj2.command.SubsystemBase;
@@ -61,10 +62,11 @@ public Shooter() {
6162
public Command PIDCMD(double newTargetRPM) {
6263

6364
targetRPM = newTargetRPM;
64-
//SmartDashboard.putNumber("PID/Shooter/Target RPM", newTargetRPM);
65+
// SmartDashboard.putNumber("PID/Shooter/Target RPM", newTargetRPM);
6566

6667
return runOnce(
6768
() -> {
69+
DriverStation.reportWarning("Shooter", false);
6870
shootController.setSetpoint(newTargetRPM, ControlType.kVelocity);
6971
});
7072
}

0 commit comments

Comments
 (0)