Skip to content
This repository has been archived by the owner on Jan 10, 2025. It is now read-only.

Implement shooter subsystem #1

Merged
merged 1 commit into from
May 15, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,8 @@ tasks.withType(JavaCompile) {
}

spotless {
enforceCheck false

java {
target fileTree('.') {
include '**/*.java'
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
package frc.robot;

public final class Constants {
public static final int driverport = 0;
public static final int shooterPort = 31;
public static final double shooterP = 0.02;
public static final double shooterI = 0.5;
public static final double shooterD = 0;
}
25 changes: 20 additions & 5 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
@@ -1,17 +1,32 @@
package frc.robot;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.subsystems.Shooter;

public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private CommandXboxController m_driver;
private Shooter m_shooter;

private RobotContainer m_robotContainer;
private Command getAutonomousCommand() {
return null;
}

@Override
public void robotInit() {
m_robotContainer = new RobotContainer();
private void configureBindings() {}

@SuppressWarnings("removal")
public Robot() {
m_driver = new CommandXboxController(Constants.driverport);
m_shooter =
new Shooter(
new CANSparkMax(Constants.shooterPort, CANSparkMaxLowLevel.MotorType.kBrushless));

configureBindings();
}

@Override
Expand All @@ -30,7 +45,7 @@ public void disabledExit() {}

@Override
public void autonomousInit() {
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
m_autonomousCommand = getAutonomousCommand();

if (m_autonomousCommand != null) {
m_autonomousCommand.schedule();
Expand Down
16 changes: 0 additions & 16 deletions src/main/java/frc/robot/RobotContainer.java

This file was deleted.

69 changes: 69 additions & 0 deletions src/main/java/frc/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
package frc.robot.subsystems;

import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Constants;

/** Our Crescendo shooter Subsystem */
public class Shooter extends SubsystemBase {
private PIDController m_pid;
private CANSparkMax m_motor;
private RelativeEncoder m_encoder;

/**
* Creates a new {@link Shooter} {@link edu.wpi.first.wpilibj2.command.Subsystem}.
*
* @param motor The motor that the shooter controls.
*/
public Shooter(CANSparkMax motor) {
m_motor = motor;
m_encoder = m_motor.getEncoder();
m_pid = new PIDController(Constants.shooterP, Constants.shooterI, Constants.shooterD);
m_pid.setTolerance(0.2, 0.5);
}

/** Acheives and maintains speed. */
private Command achieveSpeeds(double speed) {
return Commands.run(
() ->
m_motor.setVoltage(
m_pid.calculate(Units.rotationsToRadians(m_encoder.getVelocity()), speed)));
}

/**
* Speeds up the shooter until it hits the specified speed then stops.
*
* @param speed The desired speed in Radians per second.
* @return a {@link Command} to get to the desired speed.
*/
public Command spinup(double speed) {
return achieveSpeeds(speed).until(m_pid::atSetpoint);
}

/**
* Holds the shooter at the current speed setpoint.
*
* @return A {@link Command} to hold the speed at the setpoint.
*/
public Command maintain() {
return achieveSpeeds(m_pid.getSetpoint());
}

/**
* Checks if the Shooter is at its setpoint and the loop is stable.
*
* @return A {@link Trigger} from the result.
*/
public Trigger atSetpoint() {
return new Trigger(
() ->
m_pid.getSetpoint() == Units.rotationsToRadians(m_encoder.getVelocity())
&& m_pid.atSetpoint());
}
}
74 changes: 74 additions & 0 deletions vendordeps/REVLib.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
{
"fileName": "REVLib.json",
"name": "REVLib",
"version": "2024.2.4",
"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.4"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2024.2.4",
"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.4",
"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.4",
"libName": "REVLibDriver",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
}
]
}