From f9fd18d0649e6b6d74aeda3cb6902efe8da856d3 Mon Sep 17 00:00:00 2001 From: taj-maharj08 Date: Tue, 20 Feb 2024 14:34:36 -0500 Subject: [PATCH] Commit before going to WPI. Put Climber and ARM together untested --- src/main/java/frc/robot/Robot.java | 6 +----- src/main/java/frc/robot/Subsystems.java | 2 +- src/main/java/frc/robot/arm/Arm.java | 2 +- 3 files changed, 3 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 2649072..690cbda 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -135,11 +135,7 @@ public Robot() { m_operatorController .leftTrigger() - .whileTrue( - Commands.parallel( - m_intake.feed(), - m_arm.goToSetpoint(1.232, -2.753, 0.0, 0.0), - m_shooter.ShooterOn())) + .whileTrue(Commands.parallel(m_intake.feed(), m_arm.goToSetpoint(1.232, -2.753, 0.0, 0.0))) .onFalse( Commands.sequence(m_arm.goToSetpoint(ArmSetpoints.kStowed), m_shooter.ShooterOff())); diff --git a/src/main/java/frc/robot/Subsystems.java b/src/main/java/frc/robot/Subsystems.java index 2b4a7e3..77aac4d 100644 --- a/src/main/java/frc/robot/Subsystems.java +++ b/src/main/java/frc/robot/Subsystems.java @@ -85,4 +85,4 @@ public static Climber createSparkMAXClimber() { public static Climber createBlankClimber() { return new Climber(new ClimberIO() {}); } -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/arm/Arm.java b/src/main/java/frc/robot/arm/Arm.java index d3c872b..341206f 100644 --- a/src/main/java/frc/robot/arm/Arm.java +++ b/src/main/java/frc/robot/arm/Arm.java @@ -61,7 +61,7 @@ public class Arm extends SubsystemBase { elbowkS.initDefault(0.55); elbowCruiseVelocityRadPerSec.initDefault(5.0); elbowMaxAccelerationRadPerSecSq.initDefault(8.0); - wristkP.initDefault(0.8); + wristkP.initDefault(1.3); wristkD.initDefault(0); wristkS.initDefault(0.3); wristCruiseVelocityRadPerSec.initDefault(4.0);