Skip to content

Commit ccf1ab9

Browse files
committed
Merge branch 'shooter' into Hopper
2 parents 9fa9f59 + 7de998e commit ccf1ab9

File tree

5 files changed

+345
-0
lines changed

5 files changed

+345
-0
lines changed

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

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,12 @@ public final class Constants {
1818
public static final Mode simMode = Mode.SIM;
1919
public static final Mode currentMode = RobotBase.isReal() ? Mode.REAL : simMode;
2020

21+
public static class ShooterConstants {
22+
23+
public static final int SHOOTERID = 8;
24+
public static final int HOODID = 9;
25+
}
26+
2127
public static enum Mode {
2228
/** Running on a real robot. */
2329
REAL,

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

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
import frc.robot.subsystems.drive.ModuleIO;
2525
import frc.robot.subsystems.drive.ModuleIOSim;
2626
import frc.robot.subsystems.drive.ModuleIOTalonFX;
27+
import frc.robot.subsystems.shooter.Shooter;
2728
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
2829

2930
/**
@@ -42,8 +43,14 @@ public class RobotContainer {
4243
// Dashboard inputs
4344
private final LoggedDashboardChooser<Command> autoChooser;
4445

46+
private final Shooter m_Shooter;
47+
4548
/** The container for the robot. Contains subsystems, OI devices, and commands. */
4649
public RobotContainer() {
50+
51+
// Define Shooter
52+
m_Shooter = new Shooter();
53+
4754
switch (Constants.currentMode) {
4855
case REAL:
4956
// Real robot, instantiate hardware IO implementations
@@ -160,6 +167,9 @@ private void configureButtonBindings() {
160167
new Pose2d(drive.getPose().getTranslation(), Rotation2d.kZero)),
161168
drive)
162169
.ignoringDisable(true));
170+
171+
controller.rightBumper().onFalse(m_Shooter.PIDCMD(500));
172+
controller.rightBumper().onTrue(m_Shooter.PIDCMD(0));
163173
}
164174

165175
/**
Lines changed: 87 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,87 @@
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.shooter;
6+
7+
import com.revrobotics.PersistMode;
8+
import com.revrobotics.RelativeEncoder;
9+
import com.revrobotics.ResetMode;
10+
import com.revrobotics.spark.SparkBase.ControlType;
11+
import com.revrobotics.spark.SparkClosedLoopController;
12+
import com.revrobotics.spark.SparkLowLevel.MotorType;
13+
import com.revrobotics.spark.SparkMax;
14+
import com.revrobotics.spark.config.SparkMaxConfig;
15+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
16+
import edu.wpi.first.wpilibj2.command.Command;
17+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
18+
import frc.robot.Constants;
19+
20+
public class Hood extends SubsystemBase {
21+
/** Creates a new Hood. */
22+
SparkMax hoodMax = new SparkMax(Constants.ShooterConstants.HOODID, MotorType.kBrushless);
23+
24+
// To use a SparkMax, we create a SparkMax object. To use PID, we have to use the PID Object.
25+
// REVLib have their own PID Object called SparkClosedLoopController.
26+
SparkClosedLoopController hoodController = hoodMax.getClosedLoopController();
27+
28+
// Encoder: A sensor that measures the amount of rotations
29+
RelativeEncoder hoodEncoder;
30+
31+
// PID
32+
double kP = 0.1;
33+
double kI = 0.0;
34+
double kD = 3.0;
35+
double targetRPM = 0.0;
36+
37+
// pid config
38+
SparkMaxConfig hoodConfig = new SparkMaxConfig();
39+
40+
public Hood() {
41+
// initialize encoder
42+
hoodEncoder = hoodMax.getEncoder();
43+
44+
// Set PID gains
45+
hoodConfig.closedLoop.p(kP).i(kI).d(kD);
46+
47+
// dropper config
48+
hoodMax.configure(
49+
hoodConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
50+
51+
// For Elastic and Advantage
52+
53+
SmartDashboard.putNumber("PID/Hood/kP", kP);
54+
SmartDashboard.putNumber("PID/Hood/kI", kI);
55+
SmartDashboard.putNumber("PID/Hood/kD", kD);
56+
SmartDashboard.putNumber("PID/Hood/Target RPM", targetRPM);
57+
}
58+
59+
/*
60+
* Hint: New Commands and Methods go here
61+
*/
62+
public Command PIDCMD(double newTargetRPM) {
63+
64+
// advantage scope (?)
65+
targetRPM = newTargetRPM;
66+
67+
return runOnce(
68+
() -> {
69+
hoodController.setSetpoint(newTargetRPM, ControlType.kVelocity);
70+
});
71+
}
72+
73+
@SuppressWarnings("unused")
74+
@Override
75+
public void periodic() {
76+
// This method will be called once per scheduler run
77+
// For Elastic and Advtange Scope
78+
double newP = SmartDashboard.getNumber("PID/Hood/kP", kP);
79+
double newI = SmartDashboard.getNumber("PID/Hood/kI", kI);
80+
double newD = SmartDashboard.getNumber("PID/Hood/kD", kD);
81+
double newTargetRPM = SmartDashboard.getNumber("Target RPM", targetRPM);
82+
83+
SmartDashboard.putNumber("PID/Hood/Dropper Setpoint", targetRPM); // Setpoint
84+
SmartDashboard.putNumber(
85+
"PID/Hood/Dropper Velocity", hoodEncoder.getVelocity()); // Actual velocity
86+
}
87+
}
Lines changed: 109 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,109 @@
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.shooter;
6+
7+
import com.revrobotics.PersistMode;
8+
import com.revrobotics.RelativeEncoder;
9+
import com.revrobotics.ResetMode;
10+
import com.revrobotics.sim.SparkMaxSim;
11+
import com.revrobotics.spark.SparkBase.ControlType;
12+
import com.revrobotics.spark.SparkClosedLoopController;
13+
import com.revrobotics.spark.SparkLowLevel.MotorType;
14+
import com.revrobotics.spark.SparkMax;
15+
import com.revrobotics.spark.config.SparkMaxConfig;
16+
import edu.wpi.first.math.system.plant.DCMotor;
17+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
18+
import edu.wpi.first.wpilibj2.command.Command;
19+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
20+
import frc.robot.Constants;
21+
22+
public class Shooter extends SubsystemBase {
23+
/** Creates a new Shooter. */
24+
SparkMax Flywheel = new SparkMax(Constants.ShooterConstants.SHOOTERID, MotorType.kBrushless);
25+
26+
SparkMaxSim FlywheelSim = new SparkMaxSim(Flywheel, DCMotor.getNEO(1));
27+
28+
// pid
29+
SparkClosedLoopController shootController = Flywheel.getClosedLoopController();
30+
31+
// Encoder: A sensor that measures the amount of rotations
32+
RelativeEncoder flywheelEncoder;
33+
34+
// PID
35+
double kP = 0.1;
36+
double kI = 0.0;
37+
double kD = 3.0;
38+
double targetRPM = 0.0;
39+
40+
// pid config
41+
SparkMaxConfig ShooterConfig = new SparkMaxConfig();
42+
43+
public Shooter() {
44+
// initialize encoder
45+
flywheelEncoder = Flywheel.getEncoder();
46+
47+
// Set PID gains
48+
ShooterConfig.closedLoop.p(kP).i(kI).d(kD);
49+
50+
// dropper config
51+
Flywheel.configure(
52+
ShooterConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
53+
54+
// For Elastic and Advantage
55+
SmartDashboard.putNumber("PID/Shooter/kP", kP);
56+
SmartDashboard.putNumber("PID/Shooter/kI", kI);
57+
SmartDashboard.putNumber("PID/Shooter/kD", kD);
58+
SmartDashboard.putNumber("PID/Shooter/Target RPM", 0.0);
59+
}
60+
61+
public Command PIDCMD(double newTargetRPM) {
62+
63+
targetRPM = newTargetRPM;
64+
//SmartDashboard.putNumber("PID/Shooter/Target RPM", newTargetRPM);
65+
66+
return runOnce(
67+
() -> {
68+
shootController.setSetpoint(newTargetRPM, ControlType.kVelocity);
69+
});
70+
}
71+
72+
@SuppressWarnings("unused")
73+
@Override
74+
public void periodic() {
75+
// For Elastic and Advtange Scope
76+
double newP = SmartDashboard.getNumber("PID/Shooter/kP", kP);
77+
double newI = SmartDashboard.getNumber("PID/Shooter/kI", kI);
78+
double newD = SmartDashboard.getNumber("PID/Shooter/kD", kD);
79+
// double newTTargetRPM = SmartDashboard.getNumber("PID/Shooter/Target RPM", targetRPM);
80+
81+
SmartDashboard.putNumber(
82+
"PID/Shooter/Dropper Output", flywheelEncoder.getPosition()); // Setpoint
83+
84+
SmartDashboard.putNumber("PID/Shooter/Target RPM", shootController.getSetpoint()); //
85+
// Setpoint
86+
SmartDashboard.putNumber(
87+
"PID/Shooter/Dropper Velocity", flywheelEncoder.getVelocity()); // Actual velocity
88+
89+
// SmartDashboard.updateValues();
90+
}
91+
92+
@Override
93+
public void simulationPeriodic() {
94+
// In this method, we update our simulation of what our arm is doing
95+
// First, we set our "inputs" (voltages)
96+
97+
// Next, we update it. The standard loop time is 20ms.
98+
99+
// Now, we update the Spark MAX
100+
FlywheelSim.iterate(
101+
FlywheelSim.getSetpoint(),
102+
12, // Simulated battery voltage, in Volts
103+
0.02); // Time interval, in Seconds
104+
105+
// SimBattery estimates loaded battery voltages
106+
// This should include all motors being simulated
107+
108+
}
109+
}

vendordeps/REVLib.json

Lines changed: 133 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,133 @@
1+
{
2+
"fileName": "REVLib.json",
3+
"name": "REVLib",
4+
"version": "2026.0.1",
5+
"frcYear": "2026",
6+
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
7+
"mavenUrls": [
8+
"https://maven.revrobotics.com/"
9+
],
10+
"jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2026.json",
11+
"javaDependencies": [
12+
{
13+
"groupId": "com.revrobotics.frc",
14+
"artifactId": "REVLib-java",
15+
"version": "2026.0.1"
16+
}
17+
],
18+
"jniDependencies": [
19+
{
20+
"groupId": "com.revrobotics.frc",
21+
"artifactId": "REVLib-driver",
22+
"version": "2026.0.1",
23+
"skipInvalidPlatforms": true,
24+
"isJar": false,
25+
"validPlatforms": [
26+
"windowsx86-64",
27+
"linuxarm64",
28+
"linuxx86-64",
29+
"linuxathena",
30+
"linuxarm32",
31+
"osxuniversal"
32+
]
33+
},
34+
{
35+
"groupId": "com.revrobotics.frc",
36+
"artifactId": "RevLibBackendDriver",
37+
"version": "2026.0.1",
38+
"skipInvalidPlatforms": true,
39+
"isJar": false,
40+
"validPlatforms": [
41+
"windowsx86-64",
42+
"linuxarm64",
43+
"linuxx86-64",
44+
"linuxathena",
45+
"linuxarm32",
46+
"osxuniversal"
47+
]
48+
},
49+
{
50+
"groupId": "com.revrobotics.frc",
51+
"artifactId": "RevLibWpiBackendDriver",
52+
"version": "2026.0.1",
53+
"skipInvalidPlatforms": true,
54+
"isJar": false,
55+
"validPlatforms": [
56+
"windowsx86-64",
57+
"linuxarm64",
58+
"linuxx86-64",
59+
"linuxathena",
60+
"linuxarm32",
61+
"osxuniversal"
62+
]
63+
}
64+
],
65+
"cppDependencies": [
66+
{
67+
"groupId": "com.revrobotics.frc",
68+
"artifactId": "REVLib-cpp",
69+
"version": "2026.0.1",
70+
"libName": "REVLib",
71+
"headerClassifier": "headers",
72+
"sharedLibrary": false,
73+
"skipInvalidPlatforms": true,
74+
"binaryPlatforms": [
75+
"windowsx86-64",
76+
"linuxarm64",
77+
"linuxx86-64",
78+
"linuxathena",
79+
"linuxarm32",
80+
"osxuniversal"
81+
]
82+
},
83+
{
84+
"groupId": "com.revrobotics.frc",
85+
"artifactId": "REVLib-driver",
86+
"version": "2026.0.1",
87+
"libName": "REVLibDriver",
88+
"headerClassifier": "headers",
89+
"sharedLibrary": false,
90+
"skipInvalidPlatforms": true,
91+
"binaryPlatforms": [
92+
"windowsx86-64",
93+
"linuxarm64",
94+
"linuxx86-64",
95+
"linuxathena",
96+
"linuxarm32",
97+
"osxuniversal"
98+
]
99+
},
100+
{
101+
"groupId": "com.revrobotics.frc",
102+
"artifactId": "RevLibBackendDriver",
103+
"version": "2026.0.1",
104+
"libName": "BackendDriver",
105+
"sharedLibrary": true,
106+
"skipInvalidPlatforms": true,
107+
"binaryPlatforms": [
108+
"windowsx86-64",
109+
"linuxarm64",
110+
"linuxx86-64",
111+
"linuxathena",
112+
"linuxarm32",
113+
"osxuniversal"
114+
]
115+
},
116+
{
117+
"groupId": "com.revrobotics.frc",
118+
"artifactId": "RevLibWpiBackendDriver",
119+
"version": "2026.0.1",
120+
"libName": "REVLibWpi",
121+
"sharedLibrary": true,
122+
"skipInvalidPlatforms": true,
123+
"binaryPlatforms": [
124+
"windowsx86-64",
125+
"linuxarm64",
126+
"linuxx86-64",
127+
"linuxathena",
128+
"linuxarm32",
129+
"osxuniversal"
130+
]
131+
}
132+
]
133+
}

0 commit comments

Comments
 (0)