Skip to content

Commit c7f12dc

Browse files
Merge pull request #58 from aaditsangvikar/dev
arm tuning, intake current limits
2 parents f0ab5e8 + 286c98e commit c7f12dc

File tree

4 files changed

+36
-5
lines changed

4 files changed

+36
-5
lines changed

build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ repositories {
1414
}
1515

1616

17-
def ROBOT_MAIN_CLASS = "frc.robot.Main"
17+
def ROBOT_MAIN_CLASS = "org.blackknights.Main"
1818

1919
// Define my targets (RoboRIO) and artifacts (deployable files)
2020
// This is added by GradleRIO's backing project DeployUtils.

src/main/java/org/blackknights/RobotContainer.java

Lines changed: 31 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -102,13 +102,41 @@ private void configureBindings() {
102102

103103
elevatorSubsystem.setDefaultCommand(new BaseCommand(elevatorSubsystem, armSubsystem));
104104

105+
primaryController.dpadDown.whileTrue(new RunCommand(() -> swerveSubsystem.zeroGyro()));
106+
107+
// SECONDARY CONTROLLER
108+
105109
climberSubsystem.setDefaultCommand(
106110
new ClimberCommand(climberSubsystem, secondaryController));
107111

108-
primaryController.dpadDown.whileTrue(new RunCommand(() -> swerveSubsystem.zeroGyro()));
112+
// secondaryController.leftBumper.onTrue(new InstantCommand(() ->
113+
// coralQueue.stepBackwards()));
114+
// secondaryController.rightBumper.onTrue(new InstantCommand(() ->
115+
// coralQueue.stepForwards()));
116+
117+
secondaryController.aButton.whileTrue(
118+
new ElevatorArmCommand(
119+
elevatorSubsystem,
120+
armSubsystem,
121+
() -> ScoringConstants.ScoringHeights.INTAKE));
122+
123+
secondaryController.bButton.whileTrue(
124+
new ElevatorArmCommand(
125+
elevatorSubsystem, armSubsystem, () -> ScoringConstants.ScoringHeights.L2));
126+
127+
secondaryController.xButton.whileTrue(
128+
new ElevatorArmCommand(
129+
elevatorSubsystem, armSubsystem, () -> ScoringConstants.ScoringHeights.L3));
130+
131+
secondaryController.yButton.whileTrue(
132+
new ElevatorArmCommand(
133+
elevatorSubsystem, armSubsystem, () -> ScoringConstants.ScoringHeights.L4));
134+
135+
secondaryController.leftBumper.whileTrue(
136+
new IntakeCommand(intakeSubsystem, IntakeCommand.IntakeMode.INTAKE, () -> false));
109137

110-
secondaryController.leftBumper.onTrue(new InstantCommand(() -> coralQueue.stepBackwards()));
111-
secondaryController.rightBumper.onTrue(new InstantCommand(() -> coralQueue.stepForwards()));
138+
secondaryController.rightBumper.whileTrue(
139+
new IntakeCommand(intakeSubsystem, IntakeCommand.IntakeMode.OUTTAKE, () -> false));
112140
}
113141

114142
/** Runs once when the code starts */

src/main/java/org/blackknights/constants/ArmConstants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ public class ArmConstants {
1414
public static final TrapezoidProfile.Constraints PIVOT_CONSTRAINTS =
1515
new TrapezoidProfile.Constraints(PIVOT_MAX_VELOCITY, PIVOT_MAX_ACCELERATION);
1616

17-
public static final double PIVOT_ENCODER_OFFSET = 5.167;
17+
public static final double PIVOT_ENCODER_OFFSET = 1.581; // 5.167
1818

1919
public static final double PIVOT_KS = 0.0;
2020
public static final double PIVOT_KG = 0.0;

src/main/java/org/blackknights/subsystems/IntakeSubsystem.java

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,9 @@ public class IntakeSubsystem extends SubsystemBase {
1212
/** Create a new intake subsystem */
1313
public IntakeSubsystem() {
1414
motor.setInverted(false);
15+
motor.enableCurrentLimit(true);
16+
motor.configContinuousCurrentLimit(20);
17+
motor.configPeakCurrentLimit(0);
1518
}
1619

1720
/**

0 commit comments

Comments
 (0)