Skip to content

Commit

Permalink
Fix stuff
Browse files Browse the repository at this point in the history
Co-authored-by: Ardian Agoes <ardianagoes@users.noreply.github.com>
Co-authored-by: ilovemarmot <Traceylin023@users.noreply.github.com>
Co-authored-by: jopy-man <jopy-man@users.noreply.github.com>
  • Loading branch information
4 people committed Jan 24, 2024
1 parent 9b8c013 commit 79f0610
Show file tree
Hide file tree
Showing 5 changed files with 27 additions and 57 deletions.
4 changes: 2 additions & 2 deletions src/main/java/com/stuypulse/robot/constants/Ports.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ public interface Gamepad {
int DEBUGGER = 2;
}
public interface Shooter {
int LEFT_MOTOR = 1; //CHANGE TO ACTUAL LATER
int RIGHT_MOTOR = 2;
int LEFT_MOTOR = 20;
int RIGHT_MOTOR = 21;
}
}
3 changes: 1 addition & 2 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,9 @@
* values that we can edit on Shuffleboard.
*/
public interface Settings {
double DT = 0.02;

public interface Shooter {
double DT = 0.02;
double GEARING = 9; //change number later
double MOMENT_OF_INERTIA = 1;

SmartNumber PODIUM_SHOT_LEFT_RPM = new SmartNumber("Shooter/Podium Shot Right RPM", 0);
Expand Down
47 changes: 12 additions & 35 deletions src/main/java/com/stuypulse/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,39 +10,17 @@
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
/* 3 motors (2 side motors, 1 placer motor)
* 3 encoders
* IR sensor
*
* variables:
* leftMotor
* rightMotor
*
*
* leftEncoder
* rightEncoder
*
*
* leftTargetRPM
* rightTargetRPM
*
*
* leftController
* rightController *
* functions:
* if IR sensor detects note: stop placer motor, then run again
*
* commands:
* run
* stop
*
*/

public abstract class Shooter extends SubsystemBase {

private static final Shooter instance;

static {
instance = new ShooterImpl();
if (RobotBase.isReal()) {
instance = new ShooterImpl();
} else {
instance = new SimShooter();
}
}

public static Shooter getInstance() {
Expand All @@ -61,13 +39,9 @@ public Shooter() {
leftController = new MotorFeedforward(Feedforward.kS, Feedforward.kV, Feedforward.kA).velocity()
.add(new PIDController(PID.kP, PID.kI, PID.kD));
rightController = new MotorFeedforward(Feedforward.kS, Feedforward.kV, Feedforward.kA).velocity()
.add(new PIDController(PID.kP, PID.kI, PID.kD));
//controllers here
.add(new PIDController(PID.kP, PID.kI, PID.kD));
}

//abstract methods: stop, getLeftRPM,...
//methods: getLeftTargetRPM, getRightTargetRPM, ... setLeftTargetRPM....

public double getLeftTargetRPM() {
return leftTargetRPM.get();
}
Expand All @@ -76,11 +50,11 @@ public double getRightTargetRPM() {
return rightTargetRPM.get();
}

public void setLeftTargetRPM(Number leftTargetRPM){
public void setLeftTargetRPM(Number leftTargetRPM) {
this.leftTargetRPM.set(leftTargetRPM);
}

public void setRightTargetRPM(Number rightTargetRPM){
public void setRightTargetRPM(Number rightTargetRPM) {
this.rightTargetRPM.set(rightTargetRPM);
}

Expand All @@ -93,6 +67,9 @@ public void setRightTargetRPM(Number rightTargetRPM){

@Override
public void periodic() {
SmartDashboard.putNumber("Shooter/Left Target RPM",getLeftTargetRPM());
SmartDashboard.putNumber("Shooter/Right Target RPM", getRightTargetRPM());

leftController.update(getLeftTargetRPM(), getLeftShooterRPM());
rightController.update(getRightTargetRPM(), getRightShooterRPM());
setLeftMotorVoltageImpl(leftController.getOutput());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.stuypulse.robot.constants.Motors;
import com.stuypulse.robot.constants.Ports;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

public class ShooterImpl extends Shooter {
Expand All @@ -16,7 +15,7 @@ public class ShooterImpl extends Shooter {
private final RelativeEncoder rightEncoder;


public ShooterImpl(){
public ShooterImpl() {
leftMotor = new CANSparkMax(Ports.Shooter.LEFT_MOTOR, MotorType.kBrushless);
rightMotor = new CANSparkMax(Ports.Shooter.RIGHT_MOTOR, MotorType.kBrushless);

Expand All @@ -29,8 +28,8 @@ public ShooterImpl(){

@Override
public void stop() {
setLeftTargetRPM(0);
setRightTargetRPM(0);
leftMotor.setVoltage(0);
rightMotor.setVoltage(0);
}

@Override
Expand All @@ -44,20 +43,17 @@ public double getRightShooterRPM() {
}

@Override
public void setLeftMotorVoltageImpl(double voltage){
public void setLeftMotorVoltageImpl(double voltage) {
leftMotor.setVoltage(voltage);
}

@Override
public void setRightMotorVoltageImpl(double voltage){
public void setRightMotorVoltageImpl(double voltage) {
rightMotor.setVoltage(voltage);
}

@Override
public void periodicallyCalled() {
SmartDashboard.putNumber("Shooter/Left Target RPM",getLeftTargetRPM());
SmartDashboard.putNumber("Shooter/Right Target RPM", getRightTargetRPM());

public void periodicallyCalled() {
SmartDashboard.putNumber("Shooter/Right RPM", getRightShooterRPM());
SmartDashboard.putNumber("Shooter/Left RPM", getLeftShooterRPM());

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import com.stuypulse.stuylib.network.SmartNumber;
import com.stuypulse.robot.constants.Settings;

import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.FlywheelSim;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
Expand All @@ -12,11 +11,10 @@ public class SimShooter extends Shooter {
private FlywheelSim rightWheel;

public SimShooter() {

leftWheel = new FlywheelSim(DCMotor.getNEO(1), Settings.Shooter.GEARING, Settings.Shooter.MOMENT_OF_INERTIA);
rightWheel = new FlywheelSim(DCMotor.getNEO(1), Settings.Shooter.GEARING, Settings.Shooter.MOMENT_OF_INERTIA);

leftWheel = new FlywheelSim(DCMotor.getNEO(1), 1, Settings.Shooter.MOMENT_OF_INERTIA);
rightWheel = new FlywheelSim(DCMotor.getNEO(1), 1, Settings.Shooter.MOMENT_OF_INERTIA);
}

public void stop() {
leftWheel.setInputVoltage(0);
rightWheel.setInputVoltage(0);
Expand All @@ -25,6 +23,7 @@ public void stop() {
public double getLeftShooterRPM() {
return leftWheel.getAngularVelocityRPM();
}

public double getRightShooterRPM() {
return rightWheel.getAngularVelocityRPM();
}
Expand All @@ -39,15 +38,14 @@ public void setLeftMotorVoltageImpl(double voltage) {

@Override
public void simulationPeriodic() {
leftWheel.update(Settings.Shooter.DT);
rightWheel.update(Settings.Shooter.DT);
leftWheel.update(Settings.DT);
rightWheel.update(Settings.DT);

SmartDashboard.putNumber("Shooter/Left Target RPM",getLeftTargetRPM());
SmartDashboard.putNumber("Shooter/Right Target RPM", getRightTargetRPM());

SmartDashboard.putNumber("Shooter/Right RPM", getRightShooterRPM());
SmartDashboard.putNumber("Shooter/Left RPM", getLeftShooterRPM());

}

}

0 comments on commit 79f0610

Please sign in to comment.