Skip to content

Commit

Permalink
Final changes from testing
Browse files Browse the repository at this point in the history
  • Loading branch information
MichaelLesirge committed Mar 3, 2024
1 parent 1045c75 commit b0eb1a8
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 17 deletions.
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -148,18 +148,18 @@ public static class IntakeShooterConstants {

public static final boolean HAS_INTAKE;

public static final boolean INTAKE_REVERSE = true;
public static final boolean INTAKE_REVERSE = false;

public static final int FLYWHEEL_MOTOR_LEFT_ID = 13;
public static final int FLYWHEEL_MOTOR_RIGHT_ID = 7;
public static final int INTAKE_MOTOR_LEFT_ID = 12;
public static final int INTAKE_MOTOR_RIGHT_ID = -1;

public static final double FLYWHEEL_SPEED_AMP = .2;
public static final double FLYWHEEL_SPEED_SPEAKER = .5;
public static final double FLYWHEEL_SPEED_AMP = .5;
public static final double FLYWHEEL_SPEED_SPEAKER = 1;

public static final double WHEEL_SPEED_AMP = .2;
public static final double WHEEL_SPEED_SPEAKER = .5;
public static final double WHEEL_SPEED_AMP = 1;
public static final double WHEEL_SPEED_SPEAKER = 1;
}

public static class RobotMovementConstants {
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,9 @@
import frc.robot.Constants.SwerveDrivetrainConstants;
import frc.robot.Constants.SwerveModuleConstants;
import frc.robot.Constants.ArmConstants;
import frc.robot.Constants.AutoConstants;
import frc.robot.commands.Autos;
import frc.robot.commands.CancelCommands;
import frc.robot.commands.ChassisRemoteControl;
import frc.robot.commands.FollowTag;
import frc.robot.commands.AimAtTag;
import frc.robot.commands.ArmRotateBy;
import frc.robot.commands.ArmRotateTo;
Expand Down Expand Up @@ -204,7 +202,9 @@ public void setUpDriveController() {
xbox.b().onTrue(cancelCommand);

xbox.a().whileTrue(new AimAtTag(drivetrain, vision, 1, inputs));
xbox.x().whileTrue(new FollowTag(drivetrain, vision, 1, AutoConstants.PREFERRED_TAG_DISTANCE));
xbox.x().onTrue(Autos.dropInAmp(arm, intakeShooter));
// xbox.x().whileTrue(new FollowTag(drivetrain, vision, 1,
// AutoConstants.PREFERRED_TAG_DISTANCE));

drivetrain.setDefaultCommand(new ChassisRemoteControl(drivetrain, inputs));
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/Autos.java
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ public static Command dropInSpeaker(Arm arm, IntakeShooter shooter) {
new SpinIntakeFlywheels(shooter, Constants.IntakeShooterConstants.FLYWHEEL_SPEED_SPEAKER),
new WaitCommand(1),
new SpinIntakeWheels(shooter, Constants.IntakeShooterConstants.WHEEL_SPEED_SPEAKER),
new WaitCommand(1),
new WaitCommand(0.25),
new SpinIntakeFlywheels(shooter, 0),
new SpinIntakeWheels(shooter, 0));
}
Expand Down
12 changes: 4 additions & 8 deletions src/main/java/frc/robot/subsystems/intake/RealShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,19 +27,15 @@ public class RealShooter extends IntakeShooter {
private final WPI_VictorSPX flywheel1;
private final WPI_VictorSPX flywheel2;

private final CANSparkMax intake1;
private final CANSparkMax intake;
// private final CANSparkMax intake2; // might not exist

public RealShooter(int flywheel1id, int flywheel2id, int intake1id, int intake2id) {
this.flywheel1 = new WPI_VictorSPX(flywheel1id);
this.flywheel2 = new WPI_VictorSPX(flywheel2id);

this.intake1 = new CANSparkMax(intake1id, CANSparkLowLevel.MotorType.kBrushless);
// this.intake2 = new CANSparkMax(intake2id,
// CANSparkLowLevel.MotorType.kBrushless);

intake1.setInverted(IntakeShooterConstants.INTAKE_REVERSE);
// intake2.setInverted(IntakeShooterConstants.INTAKE_REVERSE);
this.intake = new CANSparkMax(intake1id, CANSparkLowLevel.MotorType.kBrushless);
intake.setInverted(IntakeShooterConstants.INTAKE_REVERSE);
}

public void setFlyWheelSpeed(double speed) {
Expand All @@ -60,7 +56,7 @@ public void reverseFlywheel() {
}

public void setIntakeSpeed(double speed) {
intake1.set(speed);
intake.set(speed);
// intake2.set(speed);
}

Expand Down

0 comments on commit b0eb1a8

Please sign in to comment.