Fixed spacing

This commit is contained in:
Cayden Brackett 2025-07-09 14:49:23 -04:00
parent 908aca7bd1
commit f33f35b8f8
3 changed files with 14 additions and 10 deletions

View File

@ -17,12 +17,10 @@ import frc.robot.subsystems.DriveTrain;
import frc.robot.subsystems.Grabber; import frc.robot.subsystems.Grabber;
public class RobotContainer { public class RobotContainer {
CommandPS5Controller driver; private CommandPS5Controller driver;
private Arm arm;
Arm arm; private DriveTrain driveTrain;
private Grabber grabber;
DriveTrain driveTrain;
Grabber grabber;
public RobotContainer() { public RobotContainer() {
arm = new Arm(); arm = new Arm();
@ -39,11 +37,17 @@ public class RobotContainer {
driver::getLeftX driver::getLeftX
) )
); );
grabber.setDefaultCommand(grabber.stop()); grabber.setDefaultCommand(grabber.stop());
driver.R1().whileTrue(grabber.runGrabberMotor(1)); driver.R1().whileTrue(grabber.runGrabberMotor(1));
driver.L1().whileTrue(grabber.runGrabberMotor(-1)); driver.L1().whileTrue(grabber.runGrabberMotor(-1));
arm.setDefaultCommand(arm.stop()); arm.setDefaultCommand(arm.stop());
driver.povUp().whileTrue(arm.runArmMotor(1)); driver.povUp().whileTrue(arm.runArmMotor(1));
driver.povDown().whileTrue(arm.runArmMotor(-1)); driver.povDown().whileTrue(arm.runArmMotor(-1));
} }

View File

@ -2,7 +2,6 @@ package frc.robot.subsystems;
import java.util.function.DoubleSupplier; import java.util.function.DoubleSupplier;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; 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.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
@ -28,9 +27,9 @@ public class DriveTrain extends SubsystemBase {
drive = new DifferentialDrive(motorLeftFt, motorRightFt); drive = new DifferentialDrive(motorLeftFt, motorRightFt);
} }
public Command driveArcade(DoubleSupplier xSpeed, DoubleSupplier zRotation) { public Command driveArcade(DoubleSupplier xSpeed, DoubleSupplier zRotation) {
return run(() -> { return run(() -> {
drive.arcadeDrive(xSpeed.getAsDouble(), zRotation.getAsDouble()); drive.arcadeDrive(xSpeed.getAsDouble(), zRotation.getAsDouble());
}); });
} }

View File

@ -12,18 +12,19 @@ public class Grabber extends SubsystemBase {
private WPI_TalonSRX motorRight; private WPI_TalonSRX motorRight;
private WPI_TalonSRX motorLeft; private WPI_TalonSRX motorLeft;
public Grabber() { public Grabber() {
motorRight = new WPI_TalonSRX(GrabberConstants.kGrabberRtMotorID7); motorRight = new WPI_TalonSRX(GrabberConstants.kGrabberRtMotorID7);
motorLeft = new WPI_TalonSRX(GrabberConstants.kGrabberLtMotorID6); motorLeft = new WPI_TalonSRX(GrabberConstants.kGrabberLtMotorID6);
motorLeft.follow(motorRight); motorLeft.follow(motorRight);
} }
public Command runGrabberMotor(double speed) {
public Command runGrabberMotor(double speed) {
return run(() -> { return run(() -> {
motorRight.set(speed); motorRight.set(speed);
}); });
} }
public Command stop() { public Command stop() {
return run(() -> motorRight.set(0)); return run(() -> motorRight.set(0));
} }