From b069f2f48b6e1242499b5148ddd4ea6a5b614a1f Mon Sep 17 00:00:00 2001 From: Shaun <67600586+Fruggg@users.noreply.github.com> Date: Fri, 15 Mar 2024 12:00:49 -0400 Subject: [PATCH] Fixed Drivetrain --- src/main/java/frc/robot/Robot.java | 3 ++- src/main/java/frc/robot/RobotContainer.java | 16 +++++++++------- 2 files changed, 11 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 6a41b62..1814a8f 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -23,7 +23,8 @@ public class Robot extends TimedRobot { @Override public void robotInit() { m_robotContainer = new RobotContainer(); - SignalLogger.setPath("/media/sda1/"); + //DO NOT LEAVE THIS UNCOMMENTED DURING COMPETITION + // SignalLogger.setPath("/media/sda1/"); // SignalLogger.start(); CameraServer.startAutomaticCapture(); // Creates the CvSink and connects it to the UsbCamera diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index a4aa187..008f84d 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -77,9 +77,9 @@ public class RobotContainer { }; private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric() - .withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband - .withDriveRequestType(DriveRequestType.OpenLoopVoltage); // I want field-centric - // driving in open loop + .withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband + .withDriveRequestType(DriveRequestType.OpenLoopVoltage); // I want field-centric + // driving in open loop private final SwerveRequest.SwerveDriveBrake brake = new SwerveRequest.SwerveDriveBrake(); private final SwerveRequest.PointWheelsAt point = new SwerveRequest.PointWheelsAt(); private final Telemetry logger = new Telemetry(MaxSpeed); @@ -137,11 +137,13 @@ private void configureBindings() { .withRotationalRate(-m_driverController.getRightX() * MaxAngularRate) // Drive counterclockwise with // negative X (left) ; - drivetrain.setDefaultCommand( // Drivetrain will execute this command periodically + drivetrain.setDefaultCommand( // Drivetrain will execute this command periodically // Drive forward with negative Y (forward) - - drivetrain.applyRequest(() -> driveRequest)); - + drivetrain.applyRequest(() -> drive.withVelocityX(-m_driverController.getLeftY() * MaxSpeed) + .withVelocityY(-m_driverController.getLeftX() * MaxSpeed) // Drive left with negative X (left) + .withRotationalRate(-m_driverController.getRightX() * MaxAngularRate) // Drive counterclockwise with + // negative X (left) + )); // m_driverController.a().whileTrue(drivetrain.applyRequest(() -> brake)); /* * m_driverController.b().whileTrue(drivetrain