Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

basic Shooter Subsystem Setup #62

Merged
merged 11 commits into from
Feb 1, 2024
Merged
Show file tree
Hide file tree
Changes from 7 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 src/main/java/org/jmhsrobotics/frc2024/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@ public class Constants {
*/
public static class CAN {
public static final int kIntakeId = 32;
public static final int kShooterTopId = 33;
public static final int kShooterBottomId = 34;

};
/**
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/org/jmhsrobotics/frc2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@
import org.jmhsrobotics.frc2024.subsystems.LED.commands.RainbowLEDCommand;
import org.jmhsrobotics.frc2024.subsystems.drive.DriveSubsystem;
import org.jmhsrobotics.frc2024.subsystems.drive.commands.DriveCommand;
import org.jmhsrobotics.frc2024.subsystems.shooter.ShooterSubsystem;
import org.jmhsrobotics.frc2024.subsystems.shooter.commands.ShooterCommand;
import org.jmhsrobotics.frc2024.subsystems.drive.commands.LockAprilTag;
import org.jmhsrobotics.frc2024.subsystems.intake.IntakeSubsystem;
import org.jmhsrobotics.frc2024.subsystems.vision.VisionSubsystem;
Expand Down Expand Up @@ -38,6 +40,7 @@ public class RobotContainer implements Logged {

private final VisionSubsystem visionSubsystem = new VisionSubsystem(this.driveSubsystem);

private final ShooterSubsystem shooterSubsystem = new ShooterSubsystem();
private final LEDSubsystem ledSubsystem = new LEDSubsystem();
private final IntakeSubsystem intakeSubsystem = new IntakeSubsystem();

Expand All @@ -55,6 +58,8 @@ public RobotContainer() {
configurePathPlanner();
autoChooser = AutoBuilder.buildAutoChooser();
SmartDashboard.putData("Auto Chooser", autoChooser);
ShooterCommand shooterCommand = new ShooterCommand(2000, shooterSubsystem);
SmartDashboard.putData("Shooter Command", shooterCommand);
}

private void configurePathPlanner() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,9 @@ public class CompControl implements ControlBoard {

// TODO: Implement operator controls in the future
// =============Operator Controls=============
public double shooterInput() {
return this.operator.getRightTriggerAxis();
}

// =============Driver Controls=============
@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,19 @@

public interface ControlBoard {

// =============Operator Controls=============
// =============Operator Controls=============

// =============Driver Controls=============
public Trigger brake();
public double shooterInput();

public Trigger setZeroHeading();
// =============Driver Controls=============
public Trigger brake();

public double xInput();
public Trigger setZeroHeading();

public double yInput();
public double xInput();

public double rotationalInput();
public double yInput();

public double rotationalInput();

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
package org.jmhsrobotics.frc2024.subsystems.shooter;

import org.jmhsrobotics.frc2024.Constants;
import org.jmhsrobotics.warcore.rev.RevEncoderSimWrapper;

import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.simulation.FlywheelSim;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class ShooterSubsystem extends SubsystemBase {
private CANSparkMax topFlywheel = new CANSparkMax(Constants.CAN.kShooterTopId, MotorType.kBrushless);
private CANSparkMax bottomFlywheel = new CANSparkMax(Constants.CAN.kShooterBottomId, MotorType.kBrushless);;
private RelativeEncoder topEncoder;
private RelativeEncoder bottomEncoder;

// private double speed;

public ShooterSubsystem() {
// Initializes motor(s)
initializeMotors();
if (RobotBase.isSimulation()) {
initSim();
}
}

private void initializeMotors() {
topFlywheel.setIdleMode(IdleMode.kCoast);
topFlywheel.setSmartCurrentLimit(20);
topFlywheel.setOpenLoopRampRate(20);
topEncoder = topFlywheel.getEncoder();

bottomFlywheel.setIdleMode(IdleMode.kCoast);
bottomFlywheel.setSmartCurrentLimit(20);
bottomFlywheel.setOpenLoopRampRate(20);
bottomEncoder = bottomFlywheel.getEncoder();

bottomFlywheel.follow(topFlywheel);
}

@Override
public void periodic() {
SmartDashboard.putNumber("shooter/topRPM", getRPM());
SmartDashboard.putNumber("shooter/bottomRPM", bottomEncoder.getVelocity());
}

public double getRPM() {

return topEncoder.getVelocity();
}

public void setSpeed(double speed) {
topFlywheel.set(speed);
}

FlywheelSim flywheelSim;
RevEncoderSimWrapper encSim;
public void initSim() {
flywheelSim = new FlywheelSim(DCMotor.getNEO(1), 1, 1);
encSim = RevEncoderSimWrapper.create(topFlywheel);
}

@Override
public void simulationPeriodic() {
double motorVolts = topFlywheel.get() * 12;
flywheelSim.setInputVoltage(motorVolts);
flywheelSim.update(0.2);
encSim.setVelocity(flywheelSim.getAngularVelocityRPM());
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
package org.jmhsrobotics.frc2024.subsystems.shooter.commands;

import org.jmhsrobotics.frc2024.subsystems.shooter.ShooterSubsystem;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.Command;

public class ShooterCommand extends Command {
private ShooterSubsystem shooter;
private double targetRPM;
private PIDController pid;

public ShooterCommand(double targetRPM, ShooterSubsystem shooterSubsystem) {
this.shooter = shooterSubsystem;
this.targetRPM = targetRPM;
pid = new PIDController(.1, 0, 0);

addRequirements(this.shooter);
}

@Override
public void initialize() {
pid.reset();
pid.setSetpoint(targetRPM);
}

@Override
public boolean isFinished() {
return false;
}

@Override
public void end(boolean interrupted) {
shooter.setSpeed(0);
}

@Override
public void execute() {
double motorSpeed = pid.calculate(shooter.getRPM(), targetRPM);
shooter.setSpeed(motorSpeed);
}
m10653 marked this conversation as resolved.
Show resolved Hide resolved
}
Loading