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

Added Shooter #13

Merged
merged 2 commits into from
Jan 18, 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
10 changes: 10 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -282,4 +282,14 @@ public static class IntakeConstants {
public static final int intakeMotorOneID = 5;
public static final double intakeMotorSpeed = 0.80;
}

public static class ShooterConstants {
public static final double shooterVelocity = 0;
public static final double shooterKs = 0.353;
public static final double shooterKv = 0.353;
public static final double shooterKa = 0.353;
public static final double shooterP = 0.353;
public static final int shooterMainId = 0;
public static final int shooterFollowerId = 0;
}
}
50 changes: 50 additions & 0 deletions src/main/java/frc/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.subsystems;

import com.revrobotics.CANSparkBase.ControlType;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;

import org.photonvision.simulation.SimPhotonCamera;

import com.revrobotics.CANSparkMax;
import com.revrobotics.SparkPIDController;
import com.revrobotics.SparkPIDController.ArbFFUnits;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.ShooterConstants;
import frc.robot.util.SparkMaxUtil;

public class Shooter extends SubsystemBase {
private CANSparkMax shooterMain = new CANSparkMax(ShooterConstants.shooterMainId, MotorType.kBrushless);
private CANSparkMax shooterFollower = new CANSparkMax(ShooterConstants.shooterFollowerId, MotorType.kBrushless);
private SimpleMotorFeedforward shooterFeedforward =
new SimpleMotorFeedforward(
ShooterConstants.shooterKs, ShooterConstants.shooterKv, ShooterConstants.shooterKa);

private SparkPIDController shooterPID = shooterMain.getPIDController();

/** Creates a new Shooter. */
public Shooter() {
shooterMain.restoreFactoryDefaults();
shooterFollower.follow(shooterMain, true);
shooterMain.setIdleMode(IdleMode.kCoast);
SparkMaxUtil.configureFollower(shooterFollower);

shooterPID.setP(ShooterConstants.shooterP);
}

public void setMotorSpeed(double velocity) {
double feedForward = shooterFeedforward.calculate(velocity);

shooterPID.setReference(velocity, ControlType.kVelocity, 0, feedForward, ArbFFUnits.kVoltage);
}

@Override
public void periodic() {
// This method will be called once per scheduler run
}
}
Loading