From dffa504e1a68d3b85cb511137a8a8bffbe4a4377 Mon Sep 17 00:00:00 2001 From: Ethan Porter Date: Sat, 20 Jan 2024 08:51:59 -0500 Subject: [PATCH 1/6] added ShooterIOSparkMax --- .../subsystems/shooter/ShooterIOSparkMax.java | 32 ++++++++ vendordeps/REVLib.json | 74 +++++++++++++++++++ 2 files changed, 106 insertions(+) create mode 100644 src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java create mode 100644 vendordeps/REVLib.json diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java new file mode 100644 index 00000000..b7a203dd --- /dev/null +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java @@ -0,0 +1,32 @@ +package frc.robot.subsystems.shooter; + +import com.revrobotics.CANSparkLowLevel.MotorType; +import com.revrobotics.CANSparkMax; +import com.revrobotics.RelativeEncoder; +import edu.wpi.first.math.util.Units; + +public class ShooterIOSparkMax implements ShooterIO { + private static final double GEAR_RATIO = 1.5; + + private final CANSparkMax leader = new CANSparkMax(0, MotorType.kBrushless); + private final CANSparkMax follower = new CANSparkMax(1, MotorType.kBrushless); + private final RelativeEncoder encoder = leader.getEncoder(); + + public ShooterIOSparkMax() { + leader.setInverted(false); + follower.follow(leader, false); + } + + @Override + public void updateInputs(ShooterIOInputs inputs) { + inputs.velocityRadPerSec = + Units.rotationsPerMinuteToRadiansPerSecond(encoder.getVelocity() / GEAR_RATIO); + inputs.appliedVolts = leader.getAppliedOutput() * leader.getBusVoltage(); + } + + @Override + public void setVoltage(double volts) { + leader.setVoltage(volts); + + } +} \ No newline at end of file diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json new file mode 100644 index 00000000..0f3520e7 --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,74 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2024.2.0", + "frcYear": "2024", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2024.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2024.2.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2024.2.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2024.2.0", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2024.2.0", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file From d1590bd37a3285dcfa24be6b87bf548140d6b7a6 Mon Sep 17 00:00:00 2001 From: Ethan Porter Date: Sat, 20 Jan 2024 08:57:28 -0500 Subject: [PATCH 2/6] spotless Apply --- .../java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java index b7a203dd..d980fe97 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java @@ -19,7 +19,7 @@ public ShooterIOSparkMax() { @Override public void updateInputs(ShooterIOInputs inputs) { - inputs.velocityRadPerSec = + inputs.velocityRadPerSec = Units.rotationsPerMinuteToRadiansPerSecond(encoder.getVelocity() / GEAR_RATIO); inputs.appliedVolts = leader.getAppliedOutput() * leader.getBusVoltage(); } @@ -27,6 +27,5 @@ public void updateInputs(ShooterIOInputs inputs) { @Override public void setVoltage(double volts) { leader.setVoltage(volts); - } -} \ No newline at end of file +} From 34f0053bf25bbfa1845c657ca3d8f481961f9b00 Mon Sep 17 00:00:00 2001 From: Ethan Porter Date: Sat, 20 Jan 2024 12:01:47 -0500 Subject: [PATCH 3/6] updated gear ratio --- .../java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java index d980fe97..1f30ece4 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java @@ -6,7 +6,7 @@ import edu.wpi.first.math.util.Units; public class ShooterIOSparkMax implements ShooterIO { - private static final double GEAR_RATIO = 1.5; + private static final double GEAR_RATIO = 5.0; private final CANSparkMax leader = new CANSparkMax(0, MotorType.kBrushless); private final CANSparkMax follower = new CANSparkMax(1, MotorType.kBrushless); From cbc3b2578124dd3e5556c1b5b567fa371acd21c2 Mon Sep 17 00:00:00 2001 From: Ethan Porter Date: Sat, 20 Jan 2024 12:04:06 -0500 Subject: [PATCH 4/6] added ShooterIOSparkMax as io for tankBot --- src/main/java/frc/robot/RobotContainer.java | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index f7572c7c..b51d5126 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -10,6 +10,7 @@ import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.commands.ShooterEnable; import frc.robot.subsystems.shooter.ShooterIOSim; +import frc.robot.subsystems.shooter.ShooterIOSparkMax; import frc.robot.subsystems.shooter.ShooterSubsystem; public class RobotContainer { @@ -20,12 +21,12 @@ public RobotContainer() { controller = new CommandXboxController(0); boolean swerveBot = false; - boolean tankBot = false; + boolean tankBot = true; if (swerveBot) { shooter = null; } else if (tankBot) { - shooter = null; + shooter = new ShooterSubsystem(new ShooterIOSparkMax()); } else { shooter = new ShooterSubsystem(new ShooterIOSim()); } From 2825b657e4edf4f425b7332d263038d02f2b78e9 Mon Sep 17 00:00:00 2001 From: Ethan Porter Date: Sat, 20 Jan 2024 12:32:55 -0500 Subject: [PATCH 5/6] Added Comments --- .../frc/robot/subsystems/shooter/ShooterIOSparkMax.java | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java index 1f30ece4..39e0e528 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java @@ -6,26 +6,34 @@ import edu.wpi.first.math.util.Units; public class ShooterIOSparkMax implements ShooterIO { + // Gear ratio for the shooter mechanism private static final double GEAR_RATIO = 5.0; + //define the 2 SparkMax Controllers. A leader, and a follower private final CANSparkMax leader = new CANSparkMax(0, MotorType.kBrushless); private final CANSparkMax follower = new CANSparkMax(1, MotorType.kBrushless); + + //Gets the NEO encoder private final RelativeEncoder encoder = leader.getEncoder(); public ShooterIOSparkMax() { + // leader motor is not inverted, and set follower motor to follow the leader leader.setInverted(false); follower.follow(leader, false); } @Override public void updateInputs(ShooterIOInputs inputs) { + // Set velocityRadPerSec to the encoder velocity(rotationsPerMinute) divided by the gear ratio and converted into Radians Per Second inputs.velocityRadPerSec = Units.rotationsPerMinuteToRadiansPerSecond(encoder.getVelocity() / GEAR_RATIO); + // Get applied voltage from the leader motor inputs.appliedVolts = leader.getAppliedOutput() * leader.getBusVoltage(); } @Override public void setVoltage(double volts) { + // Set the voltage output for the leader motor leader.setVoltage(volts); } } From dcc5823545134885732975a97f93ec0acd9440ae Mon Sep 17 00:00:00 2001 From: Ethan Porter Date: Sat, 20 Jan 2024 12:33:55 -0500 Subject: [PATCH 6/6] Spotless Apply --- .../frc/robot/subsystems/shooter/ShooterIOSparkMax.java | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java index 39e0e528..07871f32 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java @@ -9,22 +9,23 @@ public class ShooterIOSparkMax implements ShooterIO { // Gear ratio for the shooter mechanism private static final double GEAR_RATIO = 5.0; - //define the 2 SparkMax Controllers. A leader, and a follower + // define the 2 SparkMax Controllers. A leader, and a follower private final CANSparkMax leader = new CANSparkMax(0, MotorType.kBrushless); private final CANSparkMax follower = new CANSparkMax(1, MotorType.kBrushless); - //Gets the NEO encoder + // Gets the NEO encoder private final RelativeEncoder encoder = leader.getEncoder(); public ShooterIOSparkMax() { - // leader motor is not inverted, and set follower motor to follow the leader + // leader motor is not inverted, and set follower motor to follow the leader leader.setInverted(false); follower.follow(leader, false); } @Override public void updateInputs(ShooterIOInputs inputs) { - // Set velocityRadPerSec to the encoder velocity(rotationsPerMinute) divided by the gear ratio and converted into Radians Per Second + // Set velocityRadPerSec to the encoder velocity(rotationsPerMinute) divided by the gear ratio + // and converted into Radians Per Second inputs.velocityRadPerSec = Units.rotationsPerMinuteToRadiansPerSecond(encoder.getVelocity() / GEAR_RATIO); // Get applied voltage from the leader motor