From 5e53702ff47cb298523ca86f9c4da30dba685b16 Mon Sep 17 00:00:00 2001 From: Abhishrek05 <90010729+Abhishrek05@users.noreply.github.com> Date: Tue, 2 Apr 2024 16:34:54 -0600 Subject: [PATCH 1/8] update rotation speed --- src/main/java/frc4388/robot/Constants.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 58513e1..fbaa647 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -23,7 +23,7 @@ import frc4388.utility.LEDPatterns; public final class Constants { public static final class SwerveDriveConstants { - public static final double MAX_ROT_SPEED = 3.5; + public static final double MAX_ROT_SPEED = 2.5; public static final double AUTO_MAX_ROT_SPEED = 1.5; public static final double MIN_ROT_SPEED = 1.0; public static double ROTATION_SPEED = MAX_ROT_SPEED; From 6a8630f14756cd0122c98c1a4c549beec5ba5507 Mon Sep 17 00:00:00 2001 From: Abhishrek05 <90010729+Abhishrek05@users.noreply.github.com> Date: Thu, 4 Apr 2024 17:34:41 -0600 Subject: [PATCH 2/8] revert --- src/main/java/frc4388/robot/RobotContainer.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index f0429f8..cdd52a1 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -160,7 +160,7 @@ public class RobotContainer { private String lastAutoName = "final_red_center_4note_taxi.auto"; private ConfigurableString autoplaybackName = new ConfigurableString("Auto Playback Name", lastAutoName); private neoJoystickPlayback autoPlayback = new neoJoystickPlayback(m_robotSwerveDrive, - lastAutoName, // () -> autoplaybackName.get(), + () -> autoplaybackName.get(), // lastAutoName, // () -> autoplaybackName.get(), new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()}, true, true); From 05b3ce17863e9a29a081e22b5d44560a1ef3ab5e Mon Sep 17 00:00:00 2001 From: Abhishrek05 <90010729+Abhishrek05@users.noreply.github.com> Date: Thu, 4 Apr 2024 17:35:26 -0600 Subject: [PATCH 3/8] false --- src/main/java/frc4388/robot/RobotContainer.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index cdd52a1..4188fe1 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -162,7 +162,7 @@ public class RobotContainer { private neoJoystickPlayback autoPlayback = new neoJoystickPlayback(m_robotSwerveDrive, () -> autoplaybackName.get(), // lastAutoName, // () -> autoplaybackName.get(), new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()}, - true, true); + true, false); //Help Simplify Shooting From 1313e17ae6b1d775ba2566e5377b4f3eeb198be7 Mon Sep 17 00:00:00 2001 From: Abhishrek05 <90010729+Abhishrek05@users.noreply.github.com> Date: Thu, 4 Apr 2024 17:37:45 -0600 Subject: [PATCH 4/8] negative one --- src/main/java/frc4388/utility/controller/VirtualController.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc4388/utility/controller/VirtualController.java b/src/main/java/frc4388/utility/controller/VirtualController.java index 709bc1d..85adb64 100644 --- a/src/main/java/frc4388/utility/controller/VirtualController.java +++ b/src/main/java/frc4388/utility/controller/VirtualController.java @@ -39,7 +39,7 @@ public class VirtualController extends GenericHID { m_axes = new double[6]; m_buttonStates = 0; m_buttonStatesLastFrame = 0; - m_pov = new short[1]; + m_pov = new short[] {-1}; } /** From 18688868016aaf82696b92532e5bfc3152691555 Mon Sep 17 00:00:00 2001 From: Daniel Carta <79732052+immortaldan10@users.noreply.github.com> Date: Thu, 2 May 2024 17:29:41 -0600 Subject: [PATCH 5/8] Added 12 speed transmission, no clutch (for now...) --- src/main/java/frc4388/robot/Constants.java | 9 ++- .../java/frc4388/robot/RobotContainer.java | 35 ---------- .../frc4388/robot/subsystems/SwerveDrive.java | 67 +++---------------- 3 files changed, 15 insertions(+), 96 deletions(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index fbaa647..386c734 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -33,9 +33,12 @@ public final class Constants { public static final double CORRECTION_MIN = 10; public static final double CORRECTION_MAX = 50; - public static final double SLOW_SPEED = 0.5; - public static final double FAST_SPEED = 1.0; - public static final double TURBO_SPEED = 4.0; + public static final double[] SPEEDS = {0.25, 0.5, 0.75, 1.0, 1.25, 1.5, 1.75, 2, 2.5, 3, 3.5, 4}; + // public static final double[] SPEEDS = {0.5, 1.0, 4.0}; + + // public static final double SLOW_SPEED = 0.5; + // public static final double FAST_SPEED = 1.0; + // public static final double TURBO_SPEED = 4.0; public static final class DefaultSwerveRotOffsets { public static final double FRONT_LEFT_ROT_OFFSET = 220; diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 4188fe1..1f0434c 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -310,7 +310,6 @@ public class RobotContainer { true); }, m_robotSwerveDrive) .withName("SwerveDrive DefaultCommand")); - m_robotSwerveDrive.setToSlow(); // ! Swerve Drive Default Command (Orientation Rotation) // m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> { @@ -505,40 +504,6 @@ public class RobotContainer { new JoystickButton(getVirtualDriverController(), XboxController.START_BUTTON) .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightAmp())) .onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180())); - - - // * /* D-Pad Stuff */ - // new Trigger(() -> getVirtualDriverController().getRawAxis(XboxController.TOP_BOTTOM_DPAD_AXIS) > 0.9) - // .onTrue(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, 1), - // new Translation2d(0, 0), - // true))) - // .onFalse(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, 0), - // new Translation2d(0, 0), - // true))); - - // new Trigger(() -> getVirtualDriverController().getRawAxis(XboxController.TOP_BOTTOM_DPAD_AXIS) > -0.9) - // .onTrue(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, -1), - // new Translation2d(0, 0), - // true))) - // .onFalse(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, 0), - // new Translation2d(0, 0), - // true))); - - // new Trigger(() -> getVirtualDriverController().getRawAxis(XboxController.LEFT_RIGHT_DPAD_AXIS) > 0.9) - // .onTrue(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(1, 0), - // new Translation2d(0, 0), - // true))) - // .onFalse(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, 0), - // new Translation2d(0, 0), - // true))); - - // new Trigger(() -> getVirtualDriverController().getRawAxis(XboxController.LEFT_RIGHT_DPAD_AXIS) > -0.9) - // .onTrue(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(-1, 0), - // new Translation2d(0, 0), - // true))) - // .onFalse(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, 0), - // new Translation2d(0, 0), - // true))); // ! /* Auto Recording */ new JoystickButton(m_autoRecorderXbox, XboxController.LEFT_BUMPER_BUTTON) diff --git a/src/main/java/frc4388/robot/subsystems/SwerveDrive.java b/src/main/java/frc4388/robot/subsystems/SwerveDrive.java index 8e00166..98feae6 100644 --- a/src/main/java/frc4388/robot/subsystems/SwerveDrive.java +++ b/src/main/java/frc4388/robot/subsystems/SwerveDrive.java @@ -92,13 +92,10 @@ public class SwerveDrive extends SubsystemBase { public void playbackDriveWithInput(Translation2d leftStick, Translation2d rightStick, boolean fieldRelative) { if (fieldRelative) { - double rot = 0; - // ! drift correction if (rightStick.getNorm() > 0.05) { rotTarget = gyro.getAngle(); - rot = rightStick.getX() * SwerveDriveConstants.ROTATION_SPEED; - // SmartDashboard.putBoolean("drift correction", false); + // SmartDashboard.putBoolean("drift correction", false); stopped = false; } else if(leftStick.getNorm() > 0.05) { if (!stopped) { @@ -107,8 +104,7 @@ public class SwerveDrive extends SubsystemBase { } // SmartDashboard.putBoolean("drift correction", true); - - rot = ((rotTarget - gyro.getAngle()) / 360) * SwerveDriveConstants.ROT_CORRECTION_SPEED; + } @@ -129,7 +125,6 @@ public class SwerveDrive extends SubsystemBase { Translation2d rightStick = new Translation2d(-rightX, rightY); if(fieldRelative) { - double rot = 0; if(rightStick.getNorm() > 0.5) { orientRotTarget = new Rotation2d(rightX, -rightY).minus(new Rotation2d(0,1)); @@ -139,7 +134,6 @@ public class SwerveDrive extends SubsystemBase { if(tmp.getDegrees() < 0) min*=-1; tmp = new Rotation2d(min * Math.PI / 180); - rot = tmp.getRadians(); // x x - y/x } Translation2d speed = leftStick.times(leftStick.getNorm() * speedAdjust); @@ -228,61 +222,18 @@ public class SwerveDrive extends SubsystemBase { // SmartDashboard.putNumber("Gyro", getGyroAngle()); } + private int GEAR = SwerveDriveConstants.SPEEDS.length /2; public void shiftDown() { - if (Math.abs(this.speedAdjust - SwerveDriveConstants.SLOW_SPEED) < .01) { - - } else if (Math.abs(this.speedAdjust - SwerveDriveConstants.FAST_SPEED) < .01) { - this.speedAdjust = SwerveDriveConstants.SLOW_SPEED; - } else { - this.speedAdjust = SwerveDriveConstants.FAST_SPEED; - + if(GEAR > 0){ + GEAR--; + this.speedAdjust = SwerveDriveConstants.SPEEDS[GEAR]; } } - public void setToSlow() { - this.speedAdjust = SwerveDriveConstants.SLOW_SPEED; - System.out.println("SLOW"); - System.out.println("SLOW"); - System.out.println("SLOW"); - System.out.println("SLOW"); - System.out.println("SLOW"); - } - - public void setToFast() { - this.speedAdjust = SwerveDriveConstants.FAST_SPEED; - System.out.println("FAST"); - System.out.println("FAST"); - System.out.println("FAST"); - System.out.println("FAST"); - System.out.println("FAST"); - } - - public void setToTurbo() { - this.speedAdjust = SwerveDriveConstants.TURBO_SPEED; - System.out.println("TURBO"); - System.out.println("TURBO"); - System.out.println("TURBO"); - System.out.println("TURBO"); - System.out.println("TURBO"); - } - public void shiftUp() { - if (Math.abs(this.speedAdjust - SwerveDriveConstants.SLOW_SPEED) < .01) { - this.speedAdjust = SwerveDriveConstants.FAST_SPEED; - } else if (Math.abs(this.speedAdjust - SwerveDriveConstants.FAST_SPEED) < .01) { - this.speedAdjust = SwerveDriveConstants.TURBO_SPEED; - } else { - - } - } - - public void toggleGear(double angle) { - if (Math.abs(this.speedAdjust - SwerveDriveConstants.Conversions.JOYSTICK_TO_METERS_PER_SECOND_SLOW) < .01 && Math.abs(angle) < 10) { - this.speedAdjust = SwerveDriveConstants.Conversions.JOYSTICK_TO_METERS_PER_SECOND_FAST; - SwerveDriveConstants.ROT_CORRECTION_SPEED = SwerveDriveConstants.CORRECTION_MIN; - } else { - this.speedAdjust = SwerveDriveConstants.Conversions.JOYSTICK_TO_METERS_PER_SECOND_SLOW; - SwerveDriveConstants.ROT_CORRECTION_SPEED = SwerveDriveConstants.CORRECTION_MIN; + if(GEAR < SwerveDriveConstants.SPEEDS.length){ + GEAR++; + this.speedAdjust = SwerveDriveConstants.SPEEDS[GEAR]; } } From 6d5655356502782fc0ec43c3fe11c8f9e78d890c Mon Sep 17 00:00:00 2001 From: C4llSqin <83995467+C4llSqin@users.noreply.github.com> Date: Tue, 7 May 2024 16:38:30 -0600 Subject: [PATCH 6/8] patches --- .github/workflows/gradle.yml | 4 ++-- autos/final_1note_stationary.auto | Bin 0 -> 11345 bytes autos/final_red_center_4note_taxi.auto | Bin 0 -> 76469 bytes .../utility/controller/VirtualController.java | 2 +- 4 files changed, 3 insertions(+), 3 deletions(-) create mode 100644 autos/final_1note_stationary.auto create mode 100644 autos/final_red_center_4note_taxi.auto diff --git a/.github/workflows/gradle.yml b/.github/workflows/gradle.yml index 9eaf0d0..7d89e58 100644 --- a/.github/workflows/gradle.yml +++ b/.github/workflows/gradle.yml @@ -13,10 +13,10 @@ jobs: runs-on: ubuntu-latest steps: - uses: actions/checkout@v1 - - name: Set up JDK 1.8 + - name: Set up JDK 17 uses: actions/setup-java@v1 with: - java-version: 1.12 + java-version: 17 - name: Change wrapper permissions run: chmod +x ./gradlew - name: Build with Gradle diff --git a/autos/final_1note_stationary.auto b/autos/final_1note_stationary.auto new file mode 100644 index 0000000000000000000000000000000000000000..f83851cdd1bb4f57568177ac80723b4358c8981a GIT binary patch literal 11345 zcmd6sPl(K69EWFiW@ly(YB|tGxk!p~k(9$;&;Tfgk>Q=fUB_xsLo-=_E1YfrR}w*KqC(P(yl+rh=9 zHO|g$+A~yZ9gUW1ZB<1ncC80Sh1j)S;ZcfR$AD2Ga7~ZDubT>wQtWyPj0&;qmBOPG zyFLJ;LhSmg@F>NupTMY)y4rn(M=5sA0HZ?e+N|&>#jahzs1UnODm+TD>pUkcp~#IDB*k5cS<35*J{>%GFG6uZ6vqeATZrSK@FuFe1$ z6=K&qg-0oN?FB}K*wx^9*g2y{K`EZ=GB7H{u3HL^QtWE*JnTHjl2wT3dZ+Lx#jXa= z!_E&ZS%q}2Zdc(^id}1fQ6Y9+PyD`-bK-yn|f z6T5DcV^ZvTXz1+3t{3E(6uatv+mtriKljI^ zU=PRd5PQv>hbykrW)gPdxvr99QtTQUIy-@@wfx(rH%E?1vFo*=vlF}O?!N5**LV;6 zQ(Uu2>0JG~JEF3=nmG?w_Hc*UHFn}XJVcI3vFnJTvlF{ckz-Qqx@hR^#I76Um=wG2 z89F<$Yn~jFVprWgTiLns(M-ZlI@e$oIVQ!f4TjE6?Al6>NwMpIp|caaPLN|#?5exd qD|+S!*UTjB#B<#x$E4Wx$k5q|T@9X5gSvN!MbE}m-8;lG*UVpBF_YW? literal 0 HcmV?d00001 diff --git a/autos/final_red_center_4note_taxi.auto b/autos/final_red_center_4note_taxi.auto new file mode 100644 index 0000000000000000000000000000000000000000..b20ab8403b4d97fd6083b9c3b6e3e2d554f754de GIT binary patch literal 76469 zcmd7bd6X2z9S87TaX|#R6y*>EMC6uB6oJ$}-6Y<4##`|W;fX;EL==~;^(dJ1SQ2U;6}RwKkxZPZUVt66KH z)fs5@1zLvzt)qa}X+R5e&E~$on!N+eYaP(q2DEmPB~~0hIZZPKOU6At_jv8zioyac zea$8|UGjE0!39fpUi~Pn*iyGPVQZweYQET!ixH&uK`LXYb)`#w`3O3`j57f--i$Q*41C6 zX{KPwJ~tLnSW%z2^#;&d4Yd4rKKXt4EiSL-ErFJQJ)ihKY(4;(m){;HpVzIxyygL| zCw=RsDQTK1SaRFL=Ibe}s88Jb+P9Ma?9f6#Pf7kdszn!_SK`;$E&R{s$y*bEdEKt9 z#INUDG`ZeL{5lR>M^MKZaKuhp2Q6lehFUL^ACqJ1>15WjAOIuGP8)MTlOqtxnMmT9a*!r3leW zwlyxgL2I(D@f0C?$+oVDZqS-+>uQP+y<}Unq8qd(+nPfWqL*yzq38y!$*|n-A+~;= zB1A9Q){^K3t;x2&qX^MUuCW4+TYtUa~DrJFoWPxzY2X zHQ9M#+If}NwY0U-OLkuR^D@A?C%Qpvvh&ipcxEaSPE<{JzdRT=Td#YE(?Yg21!!F_K7Qt+RCfEf zs{Cl{sT3bMH0hP>yk?8_BQH;9qJ;IG6CXRCK?U1dF4n8QfBN{qldhoeAZ4YaD$h54Bbm1^#j0 zzdD>J(v@#GnP_6`R9>{y$(#UT@5?cs8}9+FTAbCf8PM7XXdQ?< z4?7Ok*P>OmtIN%kE>8`&J?uD%#-|XQdLNyzHA6qIta$FSRGuu%Dt2DC0ua3*@v4d-{^ZG=3-vE=wJ+7cZ^K9#9oV9No*^qKKSf(A?a7)R}Yu{e< z9W%MvLg>Y8>vZ38bhN?~Y-@^dr3w>zDcib9TU9!kWrA%z>RXP*pv7!!skXLIEL+L8 zDzp{3mnz%(250TpQd`xweMif=dF}UGnZ(Kmj$2cu&p`rvr;#*tZ4!?nUu>_UoF3iZ9OU*Q*Ibpqe?%f znv(AZ$LMBTi-6X0+32_l$l6ksNZ_x0Z_M=EDt2D$w6!h7^7>u+9^2X}8ua{UQa_m{Q}To0XC?MNyg*y^O@Jnoa`i(emN%Ja zUC+DU%kDG@Xw8rfrS4YCdM9V=X-0nd$SLJCMy?)JpJv*u~gW@LPMy+pBPg+r4$rHt=*8Q-eOfig2OS|Ohpd@(+&OJ_f7{;3$PzWD{e zHb%?(yMZxUWqt-fa)No@8#ft%ki1&$mT3m$R)&W-MC`+XA-pUH@*&!d%YI>kc!Pt%hyQ zw?#IWv#saMShgCrwZs5shHYJJi)=1uTUVN~Y&C4_Z??$ha<=tvGnTD}ZQW~&Y%XV8nD$V$Q9I1-w$*U+ z>Q-WlY%XV89nDy_8n)Hj7TH|Rwt#JKw^DPvZ8hw?#@Qm9%h?ui?7nV)Ft^)Q!^q1W z$E+LXTGYKq+-KUC4gf?%HzQ&BZ+s~Tv1P0ysn!u;a{nAvgj>Rv3p z{$2p9HPGrx&kzB5^^;yd0P%A0xruqCcI`auUPjNCh0(uDMULejto!=vekMIP7sh>E z&w4|R(dB2!I1hVd|4;YdTdg?yeJSf2y$=`nDs%je*Hf|dF;iBi?|}*{j6PSYUM`KH z?}4(G$Ze%=P+{~x@vJ!dvngw%etjAJPh!lg$UQe2q}R7h7=1$Gwhk!KmeD69cB`|j zRWWHyI5p@0m2n&|cOM?mUt4Q~{S3Xl;^6U0dFGFbP^6fmUyzH5_P_$!fwTcL321$Rvw9W*t+qg`yZ>5F`aJA81ZW+l z_hDL%UG2Wun*5Qmy}o*$BdZ)Ya`N9_?m1Idm3r2e<>l^_?GNMgvfFO-oFg}<+~A@r z>3d&2UjkZ7Wo4<#YisbkS8jElKkR*2AwPALRh@sFKoetIwQ_@sCTgc_NtuE3)Ud5@ zsZXjf`X}dM+$yfst0mCdSAMLvUl@IBW6$d#pfy%{W1|D|Iss@+1zI-&t-FENi`p{! zuE&1PF9lj_d@KKb05dyw8?^;!eW$IuX$@&Ji99vjybjz`TlH6ek+9VTX!Vop)ov2? zYP{P#J1tPf-iM>)MwoT9wrca=(+eb(nPum7ouuoHkTG>*v~D(I*=pE%y=;qYE@xY- z%viP>ww1O;HkY%lMl+VJhHEjpz_8Ex-fbxh`8G}2N_Jj7C^Ep(zsm`*E(PW_1!&zs z_d~5O8SkA7|x9cf!4F4QT+}AJqOE4Dl-#fUQ2-12cq%EAF{as^4g@2m-nnb z!F{*`XZ6{`w^G5B-1+#2}4zTXi?R?0&k&~o5!#-XM=)MN^p)+F#YuMJC z+Vc9)1tXjDY^xGzZO2&$7Xz)~K&w>Lt1%*}&!c%R1Z%kG#=)o3vkibXUSDG;e$F2} zS$NM56V1#04*0>>3vV2yu!W7}=a> zTg!ykk6eD}m|^qQur2RtW!|76m29gfBw&GRw)ItkpdpL6R^Oo^0Si>Kt)mJA4Ozst zfa5vzJvU_I3skf7()aWV1P?4?Tk`^eBFwTaeTO6h;;q8Ao{w(Onrv$cMTlOqt<}*D zT9a)xP=x3u*XjoxOQ+x9==so^?7WVo2+>Qnb#ior)?{1bDMIv;ZB34D(3))PpA;c_ z$*|n<0s7q+-Jmtu)-x0#ddaq4i*C@GZ0jA05WVDD{i73lO}5oehlo7Ewz@|q^onc? z)AqWrul|^}S6Soqu8BOs-iK#LCiIGI3p2)o+J~5N9hC(f-=@EQf~F6Lb%K4op0$QH zR$yBzj8N7JhUJdG(SN5kw6Ox$8h{yF%m${IkS>37>`KD=aGV=1Pn z3jPKGEeV!v>llh867MfMK;H)tpOb1U*?H;j0|KnurK9oySmm-DW<3M6s({v4IBQ@D z(CPrRdIGJXKx+)pI!1cWsFQCu2A(BnquPyu(}312pmi6}dI)C?Dh67efYv~uH411Q z3$)G#TGN5njX>*PKr02bRsyYhptTcc4c-%Ibp~2}f!0`{bso_ABhZ=ww4MT5!1i$P z2f)12K^Qr|}-{7nv zdjPF2K&ubXDg#>MarY{R+$Fv5XeNJObjV}U>sbk~7D?|3Gr(E_wARZ7sC&ypYJt{H zoHg`7pmiwFDx=>-PX3%9Iv;4gAieKT0`giTyE?G5p(qzRmZAR%GJul_SppT9*N>sX%KM(3%UhyeFfO^YA%fUateKl|btgptT)m9X1ANodmQl z1X@=DEl12&zjc@V``2N&i8<=GkO9_Qp!EpQdIe~`1+>=Vti#&^twBI*4A43OXq^YN zCIYSLKx-Dzx&vt45408lt=EB81 Date: Tue, 7 May 2024 16:41:46 -0600 Subject: [PATCH 7/8] Disable camera --- src/main/java/frc4388/robot/RobotContainer.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 3e0325c..570e650 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -178,7 +178,7 @@ public class RobotContainer { DriverStation.silenceJoystickConnectionWarning(true); - CameraServer.startAutomaticCapture(); + // CameraServer.startAutomaticCapture(); /* Default Commands */ // drives the robot with a two-axis input from the driver controller @@ -371,8 +371,8 @@ public class RobotContainer { } /** - * This method is used to replcate {@link Trigger Triggers} for {@link VirtualController Virtual Controllers}. - * Please use {@link RobotContainer#DualJoystickButton} for standard buttons. + * This method is used to replcate {@link Trigger Triggers} for {@link VirtualController Virtual Controllers}.

+ * Please use {@link RobotContainer#DualJoystickButton} in {@link RobotContainer#configureButtonBindings} for standard buttons. */ private void configureVirtualButtonBindings() { From 1d2f77299341ddcc57fbdc468b1ca32ca4b953da Mon Sep 17 00:00:00 2001 From: C4llSqin <83995467+C4llSqin@users.noreply.github.com> Date: Tue, 7 May 2024 17:07:14 -0600 Subject: [PATCH 8/8] finalize cleanup --- .../java/frc4388/robot/RobotContainer.java | 29 +------------------ 1 file changed, 1 insertion(+), 28 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 570e650..bac8be0 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -204,12 +204,6 @@ public class RobotContainer { } - // private void changeAuto() { - // autoPlayback.unloadAuto(); - // autoPlayback.loadAuto(); - // lastAutoName = autoplaybackName.get(); - // System.out.println("AUTO: Changed auto to; `" + lastAutoName + "`"); - // } /** * Use this method to define your button->command mappings. Buttons can be * created by instantiating a {@link GenericHID} or one of its subclasses @@ -278,18 +272,6 @@ public class RobotContainer { true, false)) .onFalse(new InstantCommand()); - // new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) - // .whileTrue(new JoystickRecorder(m_robotSwerveDrive, - // () -> getDeadbandedDriverController().getLeftX(), - // () -> getDeadbandedDriverController().getLeftY(), - // () -> getDeadbandedDriverController().getRightX(), - // () -> getDeadbandedDriverController().getRightY(), - // "Taxi.txt")) - // .onFalse(new InstantCommand()); - - // new JoystickButton(getDeadbandedDriverController(), XboxController.LEFT_BUMPER_BUTTON) - // .onTrue(new JoystickPlayback(m_robotSwerveDrive, "Taxi.txt")) - // .onFalse(new InstantCommand()); // ! /* Speed */ new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) // final .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUp())); @@ -304,12 +286,7 @@ public class RobotContainer { new Trigger(() -> getDeadbandedDriverController().getPOV() == 90) .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUpRot())); - // new JoystickButton(getDeadbandedDriverController(), XboxController.Y_BUTTON) - // .whileTrue(new InstantCommand(() -> - // m_robotSwerveDrive.driveWithInput(new Translation2d(0, 1), - // new Translation2d(0, 0), - // true), m_robotSwerveDrive)); - + //? /* Operator Buttons */ @@ -349,10 +326,6 @@ public class RobotContainer { //spins up shooter, no wind down DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.LEFT_JOYSTICK_BUTTON) .onTrue(new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter)); - - // DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.RIGHT_JOYSTICK_BUTTON) - // .onTrue(new InstantCommand(() -> m_robotIntake.talonSpinIntakeMotor(), m_robotIntake)) - // .onFalse(new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake)); DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.RIGHT_JOYSTICK_BUTTON) .onTrue(emergencyRetract);