From b8f8c99bfd8e48756fb21ed23bf97942e34c7e05 Mon Sep 17 00:00:00 2001 From: IsaacThoman Date: Fri, 22 Sep 2023 11:50:39 -0400 Subject: [PATCH] have arm not move while driving, brake mode on drivetrain --- .github/workflows/gradle.yml | 27 +++++++++++++++++++ src/main/java/frc/robot/RobotContainer.java | 4 +-- .../robot/subsystems/GrabberSubsystem.java | 6 ++++- .../robot/subsystems/drive/SwerveModule.java | 2 +- 4 files changed, 35 insertions(+), 4 deletions(-) create mode 100644 .github/workflows/gradle.yml diff --git a/.github/workflows/gradle.yml b/.github/workflows/gradle.yml new file mode 100644 index 0000000..eca5dde --- /dev/null +++ b/.github/workflows/gradle.yml @@ -0,0 +1,27 @@ +name: Gradle build +on: + push: + branches: ["**"] + pull_request: + branches: ["**"] +jobs: + gradle: + strategy: + matrix: + os: [ubuntu-latest] + runs-on: ${{ matrix.os }} + steps: + - uses: actions/checkout@v3 + - uses: actions/setup-java@v3 + with: + distribution: temurin + java-version: 17 + + - name: Setup Gradle + uses: gradle/gradle-build-action@v2 + + - name: Set gradlew executable + run: chmod +x ./gradlew + + - name: Execute Gradle build + run: ./gradlew build diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 940b524..d0921b3 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -43,7 +43,7 @@ public RobotContainer() { // Configure the trigger bindings configureBindings(); - grabberSub.setDefaultCommand(new RunCommand(()-> grabberSub.joystickDrive(xboxController.getLeftY(),xboxController.getRightY()), grabberSub)); + grabberSub.setDefaultCommand(new RunCommand(()-> grabberSub.joystickDrive(xboxController.getLeftY(),xboxController.getRightY(), xboxController.getLeftBumper()), grabberSub)); efSub.setDefaultCommand(new RunCommand(()->efSub.driveThing(xboxController.getLeftTriggerAxis() - xboxController.getRightTriggerAxis()),efSub)); swerveSubsystem.setDefaultCommand(new RunCommand(()->swerveSubsystem.joystickDrive(0,0,0),swerveSubsystem)); } @@ -59,7 +59,7 @@ public RobotContainer() { * joysticks}. */ private void configureBindings() { - new JoystickButton(xboxController, XboxController.Button.kA.value).whileTrue(new RunCommand(()->grabberSub.joystickDrive(operator1.getY()*0.5,operator2.getY()*0.5),grabberSub)); + new JoystickButton(xboxController, XboxController.Button.kA.value).whileTrue(new RunCommand(()->grabberSub.joystickDrive(operator1.getY()*0.5,operator2.getY()*0.5, xboxController.getLeftBumper()),grabberSub)); new JoystickButton(xboxController,XboxController.Button.kB.value).whileTrue(new InstantCommand(()->grabberSub.goHome())); new JoystickButton(xboxController,XboxController.Button.kLeftBumper.value).whileTrue(new RunCommand(()->swerveSubsystem.joystickDrive(xboxController.getLeftY()*-1, xboxController.getLeftX()*-1, xboxController.getRightX()*-1),swerveSubsystem)); diff --git a/src/main/java/frc/robot/subsystems/GrabberSubsystem.java b/src/main/java/frc/robot/subsystems/GrabberSubsystem.java index 9eaf632..3629ca9 100644 --- a/src/main/java/frc/robot/subsystems/GrabberSubsystem.java +++ b/src/main/java/frc/robot/subsystems/GrabberSubsystem.java @@ -41,7 +41,11 @@ public double[] thetaPhiToXYMeters(double stageOneAng, double stageTwoAng){ } double lastControllerUpdateTime = Timer.getFPGATimestamp(); - public void joystickDrive(double stageOneSpeed, double stageTwoSpeed){ + public void joystickDrive(double stageOneSpeed, double stageTwoSpeed, boolean disabled){ + if(disabled){ + stageOneSpeed = 0; + stageTwoSpeed = 0; + } double timeSinceLastUpdate = Timer.getFPGATimestamp() - lastControllerUpdateTime; if(Math.abs(stageOneSpeed)<0.05) stageOneSpeed = 0; if(Math.abs(stageTwoSpeed)<0.05) stageTwoSpeed = 0; diff --git a/src/main/java/frc/robot/subsystems/drive/SwerveModule.java b/src/main/java/frc/robot/subsystems/drive/SwerveModule.java index 71147a9..01a4bf3 100644 --- a/src/main/java/frc/robot/subsystems/drive/SwerveModule.java +++ b/src/main/java/frc/robot/subsystems/drive/SwerveModule.java @@ -59,7 +59,7 @@ public SwerveModule(int driveMotorId, int turningMotorId, boolean driveMotorReve driveMotor.setStatusFramePeriod(StatusFrameEnhanced.Status_Brushless_Current, 251, 1000); // driveMotor.configAllSettings(Robot.ctreConfigs.swerveDriveMotor, 1000); - driveMotor.setNeutralMode(NeutralMode.Coast); + driveMotor.setNeutralMode(NeutralMode.Brake); driveMotor.setInverted(driveMotorReversed); //debug output: driveMotor.config_kF(0, 0); //debug output: driveMotor.config_kP(0, 0);