Skip to content

Commit

Permalink
Tweaks and Adjustments to Mast
Browse files Browse the repository at this point in the history
  • Loading branch information
Java4First committed Mar 28, 2024
1 parent 7d0109c commit cb8ce0e
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 14 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ public static final class MastConstants {
public static final int kMastRight = 41;
// Speed Controller Speeds
public static final double kMastSpeed = 1;
public static final int kMastCurrentLimit = 20;
public static final int kMastCurrentLimit = 30;
}

public static final class ClimberConstants {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -222,8 +222,8 @@ private void configureButtonBindings() {
DriveCommands.joystickDrive(
drive,
() -> (MathUtil.applyDeadband(-driverPad.getLeftY(), .07)),
() -> (MathUtil.applyDeadband(-driverPad.getLeftX() * .65, .07)),
() -> (MathUtil.applyDeadband(-driverPad.getRightX() * .65, .07))));
() -> (MathUtil.applyDeadband(-driverPad.getLeftX() * .75, .07)),
() -> (MathUtil.applyDeadband(-driverPad.getRightX() * .75, .07))));

// Intake Note and Load into Launcher
/*
Expand Down
23 changes: 12 additions & 11 deletions src/main/java/frc/robot/subsystems/Mast.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,11 @@ public class Mast extends SubsystemBase {
public enum Task {
INTAKING("Intaking", 35.0),
LAUNCHSUB("Launch Subwoofer", 40.0),
LAUCNHKEY("Launch Key", 60.5),
LAUCNHKEY("Launch Key", 64.5),
LAUCNHPASS("Launch Pass", 61.0),
LAUNCHAUTO("Launch Auto", 6.0),
PUTAMP("PutAmp", -26.0), // tested
PUTTRAP("PutTrap", 7.0),
PUTTRAP("PutTrap", 2.5),
CLEARJAM("Clear", 40.0),
CLIMBING("Climbing", -7.0),
TESTING("Testing", 0.0),
Expand Down Expand Up @@ -100,13 +100,13 @@ public Mast() {
// rightEncAngle = 0.0;
testingAngle = 0.0;

mastKp = 0.8;
mastKi = 0.002;
mastKd = 2.0;
double mastIWind = 100;
mastKp = 0.88;
mastKi = 0.00;
mastKd = 0.0;
double mastIWind = 150;
mastFF = 0.0;
mastMaxPosOut = 0.3;
mastMaxNegOut = -0.3;
mastMaxPosOut = 0.45;
mastMaxNegOut = -0.45;
mastSetpoint = 0.0;

mastLeft = new CANSparkMax(kMastLeft, MotorType.kBrushless);
Expand Down Expand Up @@ -202,10 +202,11 @@ public void periodic() {
leftEncAngle =
(relmastLeftEncoder.getPosition() * 360 / gearRatio); // + mastStartingAngleOffset;
// rightEncAngle =
// (relmastRightEncoder.getPosition() * 360 / gearRatio); // + mastStartingAngleOffset;
// (relmastRightEncoder.getPosition() * 360 / gearRatio); // +
// mastStartingAngleOffset;

// Remove backlash from Launcher by syncing constantly
if (counts == 50) {
if (counts == 40) {
double ABStoRel = getAbsoluteEncoderDegrees() * 37.5 / 360;
relmastLeftEncoder.setPosition(-ABStoRel);
// relmastRightEncoder.setPosition(-ABStoRel);
Expand All @@ -224,7 +225,7 @@ public void periodic() {
// Logger.recordOutput("Mast/Right_Enc", rightEncAngle);
Logger.recordOutput("Mast/Abs_Enc", getAbsoluteEncoderDegrees());
Logger.recordOutput("Mast/LeftMotorOutput", mastLeft.get());
// Logger.recordOutput("Mast/RightMotorOutput", mastRight.get());
Logger.recordOutput("Mast/Target", currentTask.getAngle());
Logger.recordOutput("Mast/Current_Tsk", currentTask.getTaskName());
}

Expand Down

0 comments on commit cb8ce0e

Please sign in to comment.