Skip to content

Commit

Permalink
fix for #24
Browse files Browse the repository at this point in the history
  • Loading branch information
BrandonS09 committed Mar 6, 2024
1 parent 53166b4 commit ec3ea78
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 7 deletions.
7 changes: 0 additions & 7 deletions src/main/java/org/carlmontrobotics/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -58,17 +58,10 @@ private void setDefaultCommands() {
// () -> ProcessedAxisValue(driverController, Axis.kRightX)),
// () -> driverController.getRawButton(OI.Driver.slowDriveButton)
// ));

arm.setDefaultCommand(new ArmTeleop(arm, () -> inputProcessing(getStickValue(manipulatorController, Axis.kLeftY))));
}

private void setBindingsDriver() {
new JoystickButton(driverController, Button.kX.value)
.whileTrue(arm.sysIdQuasistatic(SysIdRoutine.Direction.kForward));
new JoystickButton(driverController, Button.kY.value)
.whileTrue(arm.sysIdQuasistatic(SysIdRoutine.Direction.kReverse));
new JoystickButton(driverController, Button.kB.value).whileTrue(arm.sysIdDynamic(SysIdRoutine.Direction.kForward));
new JoystickButton(driverController, Button.kA.value).whileTrue(arm.sysIdDynamic(SysIdRoutine.Direction.kReverse));
// 4 cardinal directions on arrowpad
// slowmode toggle on trigger
// 3 cardinal directions on letterpad
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/org/carlmontrobotics/commands/ArmTeleop.java
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ public void initialize() {
public void execute() {
// use trapazoid math and controllerMoveArm method from arm subsytem to apply
// voltage to the motor
if (Constants.OI.JOY_THRESH == 0)
return;
double speeds = getRequestedSpeeds();
double currTime = Timer.getFPGATimestamp();
double deltaT = currTime - lastTime;
Expand Down

0 comments on commit ec3ea78

Please sign in to comment.