Skip to content

Commit

Permalink
added to each subsystem, fixed driveTrain
Browse files Browse the repository at this point in the history
  • Loading branch information
HarvardIntern committed Feb 24, 2024
1 parent cb8051a commit 5b8835b
Show file tree
Hide file tree
Showing 4 changed files with 46 additions and 15 deletions.
15 changes: 9 additions & 6 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,25 +33,28 @@ public final class Constants {

public static final class CANIds {
// SPARK MAX CAN IDs
public static final int kFrontLeftDrivingCanId = 13;
public static final int kRearLeftDrivingCanId = 7;
public static final int kFrontLeftDrivingCanId = 20;
public static final int kFrontLeftTurningCanId = 13;

public static final int kFrontRightDrivingCanId = 40;
public static final int kRearRightDrivingCanId = 55;
public static final int kRearRightTurningCanId = 12;

public static final int kFrontLeftTurningCanId = 20;
public static final int kRearLeftDrivingCanId = 7;
public static final int kRearLeftTurningCanId = 23;

public static final int kRearRightDrivingCanId = 55;
public static final int kFrontRightTurningCanId = 36;
public static final int kRearRightTurningCanId = 12;


// Intake CAN IDs

public static final int kIntakeCanID = 8;
public static final int kIntakeTurnPitchCanID = 10;

// Shooter IDs
public static final int kShooterTopMotorCanId = 29;
public static final int kShooterAngleMotorCanId = 29;
public static final int kShooterLeftMotorCanId = 59;
public static final int kShooterRightMotorCanId = 62;

//
}
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.StartEndCommand;
import edu.wpi.first.wpilibj2.command.Subsystem;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;

Expand Down Expand Up @@ -118,6 +119,14 @@ private void configureButtonBindings() {
/*◇─◇──◇─◇
✨FloopIntake✨
◇─◇──◇─◇*/
driverController.rightBumper()
.whileTrue(new RunCommand(
() -> intake.setIntakeSpeed(0.2),
intake ));
driverController.leftBumper()
.whileTrue(new RunCommand(
() -> intake.setIntakeSpeed(-0.2),
intake ));
/*
secondaryController.x()
.onTrue(new RunCommand( () -> intake.set) )
Expand Down
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/subsystems/FloopIntake.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
import frc.robot.Constants.FloopIntakeConstants;
import frc.robot.Constants.CANIds;

public class FloopIntake{
public class FloopIntake extends SubsystemBase implements Loggable{
private final CANSparkMax intake = new CANSparkMax(CANIds.kIntakeCanID, MotorType.kBrushless);
private final CANSparkMax intakeTurnPitch = new CANSparkMax(CANIds.kIntakeTurnPitchCanID, MotorType.kBrushless);

Expand Down Expand Up @@ -100,6 +100,11 @@ public void setPitchSetpoint(double setpoint) {
intakePIDController.setGoal(setpoint);
}

@Config
public void setIntakeSpeed(double speed){
intake.set(speed);
}



}
Expand Down
30 changes: 22 additions & 8 deletions src/main/java/frc/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,13 @@


public class Shooter extends SubsystemBase implements Loggable{
private final CANSparkFlex shooterMotor = new CANSparkFlex(CANIds.kShooterTopMotorCanId, MotorType.kBrushless);
private final RelativeEncoder shooterEncoder = shooterMotor.getEncoder();
private final CANSparkFlex shooterAngleMotor = new CANSparkFlex(CANIds.kShooterAngleMotorCanId, MotorType.kBrushless);
private final CANSparkFlex shooterLeft = new CANSparkFlex(CANIds.kShooterLeftMotorCanId, MotorType.kBrushless);
private final CANSparkFlex shooterRight = new CANSparkFlex(CANIds.kShooterRightMotorCanId, MotorType.kBrushless);

private final RelativeEncoder shooterEncoder = shooterAngleMotor.getEncoder();
private final RelativeEncoder shooterLeftEncoder = shooterAngleMotor.getEncoder();
private final RelativeEncoder shooterRightEncoder = shooterAngleMotor.getEncoder();

private final PIDController shooterRPMController = new PIDController(
ShooterConstants.shooterTopP,
Expand All @@ -53,9 +58,18 @@ public class Shooter extends SubsystemBase implements Loggable{
);

public Shooter(){
shooterMotor.restoreFactoryDefaults();
shooterMotor.setIdleMode(IdleMode.kCoast);
shooterMotor.burnFlash();
shooterAngleMotor.restoreFactoryDefaults();
shooterLeft.restoreFactoryDefaults();
shooterRight.restoreFactoryDefaults();


shooterAngleMotor.setIdleMode(IdleMode.kCoast);
shooterLeft.setIdleMode(IdleMode.kCoast);
shooterRight.setIdleMode(IdleMode.kCoast);

shooterAngleMotor.burnFlash();
shooterLeft.burnFlash();
shooterRight.burnFlash();

}

Expand All @@ -74,16 +88,16 @@ public double shooterRPM(){

@Config
public void setShooterSpeed(double speed){
shooterMotor.set(speed);
shooterLeft.set(speed);
shooterRight.set(speed);
}

@Config
public void setRPMSetpoint(double rpm){
shooterRPMController.setSetpoint(rpm);
}




/*◇─◇──◇─◇
✨Commands✨
◇─◇──◇─◇*/
Expand Down

0 comments on commit 5b8835b

Please sign in to comment.