From f33f35b8f81d42c49514dd6d2279ba745410842e Mon Sep 17 00:00:00 2001 From: Cayden Brackett Date: Wed, 9 Jul 2025 14:49:23 -0400 Subject: [PATCH] Fixed spacing --- src/main/java/frc/robot/RobotContainer.java | 16 ++++++++++------ .../java/frc/robot/subsystems/DriveTrain.java | 3 +-- src/main/java/frc/robot/subsystems/Grabber.java | 5 +++-- 3 files changed, 14 insertions(+), 10 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index d976918..e324f5a 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -17,12 +17,10 @@ import frc.robot.subsystems.DriveTrain; import frc.robot.subsystems.Grabber; public class RobotContainer { - CommandPS5Controller driver; - - Arm arm; - - DriveTrain driveTrain; - Grabber grabber; + private CommandPS5Controller driver; + private Arm arm; + private DriveTrain driveTrain; + private Grabber grabber; public RobotContainer() { arm = new Arm(); @@ -39,11 +37,17 @@ public class RobotContainer { driver::getLeftX ) ); + grabber.setDefaultCommand(grabber.stop()); + driver.R1().whileTrue(grabber.runGrabberMotor(1)); + driver.L1().whileTrue(grabber.runGrabberMotor(-1)); + arm.setDefaultCommand(arm.stop()); + driver.povUp().whileTrue(arm.runArmMotor(1)); + driver.povDown().whileTrue(arm.runArmMotor(-1)); } diff --git a/src/main/java/frc/robot/subsystems/DriveTrain.java b/src/main/java/frc/robot/subsystems/DriveTrain.java index 3a047d6..2697f93 100644 --- a/src/main/java/frc/robot/subsystems/DriveTrain.java +++ b/src/main/java/frc/robot/subsystems/DriveTrain.java @@ -2,7 +2,6 @@ package frc.robot.subsystems; import java.util.function.DoubleSupplier; import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; -import com.ctre.phoenix6.controls.Follower; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj2.command.Command; @@ -28,9 +27,9 @@ public class DriveTrain extends SubsystemBase { drive = new DifferentialDrive(motorLeftFt, motorRightFt); } + public Command driveArcade(DoubleSupplier xSpeed, DoubleSupplier zRotation) { return run(() -> { - drive.arcadeDrive(xSpeed.getAsDouble(), zRotation.getAsDouble()); }); } diff --git a/src/main/java/frc/robot/subsystems/Grabber.java b/src/main/java/frc/robot/subsystems/Grabber.java index fa4f994..584a68a 100644 --- a/src/main/java/frc/robot/subsystems/Grabber.java +++ b/src/main/java/frc/robot/subsystems/Grabber.java @@ -12,18 +12,19 @@ public class Grabber extends SubsystemBase { private WPI_TalonSRX motorRight; private WPI_TalonSRX motorLeft; - public Grabber() { motorRight = new WPI_TalonSRX(GrabberConstants.kGrabberRtMotorID7); motorLeft = new WPI_TalonSRX(GrabberConstants.kGrabberLtMotorID6); motorLeft.follow(motorRight); } - public Command runGrabberMotor(double speed) { + + public Command runGrabberMotor(double speed) { return run(() -> { motorRight.set(speed); }); } + public Command stop() { return run(() -> motorRight.set(0)); }