Skip to content

Commit

Permalink
added feedforward + pid to shooter
Browse files Browse the repository at this point in the history
  • Loading branch information
cherriae committed Jan 20, 2024
1 parent 6267e0b commit 3c20906
Show file tree
Hide file tree
Showing 2 changed files with 33 additions and 4 deletions.
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@ public static class Speeds {

public static final double SWERVE_DRIVE_MAX_SPEED = 8.78; // TODO: Get this value
public static final double SWERVE_DRIVE_MAX_ANGULAR_SPEED = Math.PI * 2; // Todo: Get this value

public static final double SHOOTER_MAX_SPEED = 1;
}

public static class Physical {
Expand All @@ -55,6 +57,10 @@ public static class Physical {
public static final double SWERVE_DRIVE_WHEEL_RADIUS = 0.1;
public static final double SWERVE_DRIVE_WHEEL_CIRCUMFERENCE = 2 * Math.PI * SWERVE_DRIVE_WHEEL_RADIUS;

public static final double SHOOTER_GEAR_RATIO = 1.45;
public static final double SHOOTER_FLYWHEEL_RADIUS = 1; // TODO: FIND RADIUS
public static final double SHOOTER_FLYWHEEL_CIRCUMFERENCE = 2 * Math.PI * SHOOTER_FLYWHEEL_RADIUS;


public static final double TALON_TICKS_PER_REVOLUTION = 2048;

Expand All @@ -64,6 +70,8 @@ public static class Physical {
new Translation2d(-0.292, -0.292),
new Translation2d(-0.292, 0.292)
);

public static final double SHOOTER_PID_KP = 0;
}

public static class Offsets {
Expand Down
29 changes: 25 additions & 4 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,12 @@

package frc.robot.subsystems;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

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

/**
Expand All @@ -15,11 +17,17 @@
* @author Cherine Soewingjo
*/
public class ShooterSubsystem extends SubsystemBase {
private CANSparkMax _leftMotor = new CANSparkMax(Constants.CAN.SHOOTER_LEFT, MotorType.kBrushless);
private CANSparkMax _rightMotor = new CANSparkMax(Constants.CAN.SHOOTER_RIGHT, MotorType.kBrushless);
private final CANSparkMax _leftMotor = new CANSparkMax(Constants.CAN.SHOOTER_LEFT, MotorType.kBrushless);
private final CANSparkMax _rightMotor = new CANSparkMax(Constants.CAN.SHOOTER_RIGHT, MotorType.kBrushless);

private final RelativeEncoder _leftEncoder = _leftMotor.getEncoder();

private final PIDController _shooterController = new PIDController(Constants.Physical.SHOOTER_PID_KP, 0, 0);


/** Creates a new ShooterSubsystem. */
public ShooterSubsystem() {
_rightMotor.follow(_leftMotor,true);
}


Expand All @@ -30,11 +38,24 @@ public void periodic() {

public void spinMotor(){
_leftMotor.set(-1.0);
_rightMotor.set(1.0);
}

public void stopMotors(){
_leftMotor.set(0);
_rightMotor.set(0);
}

/** Get the velocity of the back wheel (left side) in m/s. */
public double getShooterVelocity(){
double neo_rps = _leftEncoder.getVelocity() / 60;

return(neo_rps / Constants.Physical.SHOOTER_GEAR_RATIO ) * Constants.Physical.SHOOTER_FLYWHEEL_CIRCUMFERENCE;
}

/** Set the velocity of the back wheels in m/s. */
public void setVelocity(double velocity){
double flywheel_output = (velocity / Constants.Speeds.SHOOTER_MAX_SPEED); // FEEDFORWARD (main output)
double flywheel_pid = _shooterController.calculate(getShooterVelocity(), velocity); // PID for distrubances

_leftMotor.set(flywheel_output + flywheel_pid);
}
}

0 comments on commit 3c20906

Please sign in to comment.