Skip to content

Commit

Permalink
Fixed constants + changes from sat
Browse files Browse the repository at this point in the history
  • Loading branch information
HarvardIntern committed Feb 25, 2024
1 parent 5b8835b commit 914ad0f
Show file tree
Hide file tree
Showing 3 changed files with 77 additions and 52 deletions.
16 changes: 8 additions & 8 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,13 +48,13 @@ public static final class CANIds {

// Intake CAN IDs

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

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

//
}
Expand Down Expand Up @@ -164,9 +164,9 @@ public static final class TransferConstants {

public static final class ShooterConstants {

public static final double shooterTopP = 0;
public static final double shooterTopI = 0;
public static final double shooterTopD = 0;
public static final double shooterAngleP = 0;
public static final double shooterAngleI = 0;
public static final double shooterAngleD = 0.001;

}

Expand Down
95 changes: 60 additions & 35 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@ public class RobotContainer {
// Secondary controller
CommandXboxController secondaryController = new CommandXboxController(OIConstants.kSecondaryControllerPort);


SendableChooser<SequentialCommandGroup> autoSelector = new SendableChooser<>();

/**
Expand All @@ -50,21 +49,23 @@ public class RobotContainer {
public RobotContainer() {
// Configure the button bindings
configureButtonBindings();

// Configure Oblog logger
Logger.configureLoggingAndConfig(this, true);

// Auton selector config
// autoSelector.setDefaultOption("Test", new Test4And1Auto());
// autoSelector.setDefaultOption("Test", new Test4And1Auto());

autoSelector.addOption("No auto", null);

// Configure default commands

/*◇─◇──◇─◇
Drivetrain
◇─◇──◇─◇*/

/*
* ◇─◇──◇─◇
* Drivetrain
* ◇─◇──◇─◇
*/

robotDrive.setDefaultCommand(
// The left stick controls translation of the robot.
// Turning is controlled by the X axis of the right stick.
Expand All @@ -76,14 +77,14 @@ public RobotContainer() {
true, true),
robotDrive));

/*◇─◇──◇─◇
Elevator
◇─◇──◇─◇*/
/*
* ◇─◇──◇─◇
* Elevator
* ◇─◇──◇─◇
*/


}


/**
* Use this method to define your button->command mappings. Buttons can be
* created by
Expand All @@ -95,43 +96,67 @@ public RobotContainer() {
*/
private void configureButtonBindings() {

/*◇─◇──◇─◇
Drivetrain
◇─◇──◇─◇*/
/*
* ◇─◇──◇─◇
* Drivetrain
* ◇─◇──◇─◇
*/

driverController.x()
.whileTrue(new RunCommand(
() -> robotDrive.setX(),
robotDrive));

driverController.start().onTrue(new InstantCommand(()->robotDrive.zeroHeading()));
driverController.start().onTrue(new InstantCommand(() -> robotDrive.zeroHeading()));

/*
* ◇─◇──◇─◇
* ✨Shooter✨
* ◇─◇──◇─◇
*/

/*◇─◇──◇─◇
✨Shooter✨
◇─◇──◇─◇*/

driverController.y()
driverController.y()
.onTrue(new RunCommand(
() -> shooter.moveShooterAngle(0.5),
shooter));

driverController.rightTrigger()
.whileTrue(new RunCommand(
() -> shooter.setShooterSpeed(0.5),
shooter))
.onFalse(new RunCommand(
() -> shooter.setShooterSpeed(0),
shooter));

/*◇─◇──◇─◇
✨FloopIntake✨
◇─◇──◇─◇*/
driverController.rightBumper()
;
driverController.rightBumper()
.whileTrue(new RunCommand(
() -> intake.setIntakeSpeed(0.2),
intake ));
driverController.leftBumper()
() -> shooter.setShooterSpeed(1),
shooter))
.onFalse(new RunCommand(
() -> shooter.setShooterSpeed(0),
shooter));
;

driverController.b()
.whileTrue(new RunCommand(
() -> intake.setIntakeSpeed(-0.2),
intake ));
/*
secondaryController.x()
.onTrue(new RunCommand( () -> intake.set) )
() -> shooter.moveShooterAngle(-0.5),
shooter));

/*
* ◇─◇──◇─◇
* ✨FloopIntake✨
* ◇─◇──◇─◇
*/
/*
driverController.rightBumper()
.onTrue(new RunCommand(
() -> intake.setIntakeSpeed(0.2),
intake));
driverController.leftBumper()
.onTrue(new RunCommand(
() -> intake.setIntakeSpeed(-0.2),
intake));
*/

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


public class Shooter extends SubsystemBase implements Loggable{
private final CANSparkFlex shooterAngleMotor = new CANSparkFlex(CANIds.kShooterAngleMotorCanId, MotorType.kBrushless);
private final CANSparkMax shooterAngleMotor = new CANSparkMax(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,
ShooterConstants.shooterTopI,
ShooterConstants.shooterTopD
private final PIDController shooterAngleController = new PIDController(
ShooterConstants.shooterAngleP,
ShooterConstants.shooterAngleI,
ShooterConstants.shooterAngleD
);

public Shooter(){
Expand All @@ -67,6 +67,8 @@ public Shooter(){
shooterLeft.setIdleMode(IdleMode.kCoast);
shooterRight.setIdleMode(IdleMode.kCoast);

shooterLeft.setInverted(true);

shooterAngleMotor.burnFlash();
shooterLeft.burnFlash();
shooterRight.burnFlash();
Expand All @@ -91,12 +93,10 @@ public void setShooterSpeed(double speed){
shooterLeft.set(speed);
shooterRight.set(speed);
}

@Config
public void setRPMSetpoint(double rpm){
shooterRPMController.setSetpoint(rpm);
public void moveShooterAngle(double speed){
shooterAngleMotor.set(speed);
}


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

0 comments on commit 914ad0f

Please sign in to comment.