File tree Expand file tree Collapse file tree 3 files changed +10
-2
lines changed Expand file tree Collapse file tree 3 files changed +10
-2
lines changed Original file line number Diff line number Diff line change @@ -221,7 +221,7 @@ public static Translation2d[] getWheelLocationMeters() {
221221
222222 public static final double kAutoBalanceSlowDriveVel = 0.6 ; // 0.5
223223 public static final double kAutoBalanceFinalDriveVel = 1.0 ; // 0.5 0.75
224- public static final double kAutoBalanceSlowdownTimeSec = 1.15 ; // 2.3 1.6 1.3
224+ public static final double kAutoBalanceSlowdownTimeSec = 1.0 ; // 1.3-> 1.15
225225 public static final double kAutoBalanceStopThresholdDegrees = 1.5 ; // 1 0.6 1.5
226226 public static final double kAutoBalanceEdgeTriggerThreshold = 3 ; // 5
227227 public static final double kAutoBalanceAvgRollCount = 7 ; // 5 10 7
Original file line number Diff line number Diff line change @@ -571,6 +571,10 @@ private void configureMatchDashboard() {
571571 .addBoolean ("Is Elbow Ok?" , () -> armSubsystem .isElbowOk ())
572572 .withSize (1 , 1 )
573573 .withPosition (8 , 0 );
574+ Shuffleboard .getTab ("Match" )
575+ .addBoolean ("Is Navx Connected" , () -> driveSubsystem .isNavxWorking ())
576+ .withSize (1 , 1 )
577+ .withPosition (8 , 1 );
574578 }
575579
576580 private void configurePitDashboard () {
Original file line number Diff line number Diff line change @@ -190,7 +190,7 @@ public DriveSubsystem(Constants constants) {
190190
191191 swerveModules [i ].loadAndSetAzimuthZeroReference ();
192192 }
193- ahrs = new AHRS (SerialPort .Port .kUSB1 , SerialDataType .kProcessedData , (byte ) 200 );
193+ ahrs = new AHRS (SerialPort .Port .kUSB , SerialDataType .kProcessedData , (byte ) 200 );
194194 swerveDrive = new SwerveDrive (ahrs , swerveModules );
195195 swerveDrive .resetGyro ();
196196 swerveDrive .setGyroOffset (Rotation2d .fromDegrees (0 ));
@@ -743,6 +743,10 @@ public double getGyroPitch() {
743743 return ahrs .getPitch ();
744744 }
745745
746+ public boolean isNavxWorking () {
747+ return ahrs .isConnected ();
748+ }
749+
746750 public void lockZero () {
747751 SwerveModule [] swerveModules = swerveDrive .getSwerveModules ();
748752 for (int i = 0 ; i < 4 ; i ++) {
You can’t perform that action at this time.
0 commit comments