Minor shuffleboard changes
This commit is contained in:
parent
40e53305e0
commit
4e2cb68c52
@ -16,6 +16,8 @@ import java.util.function.DoubleSupplier;
|
|||||||
import com.kauailabs.navx.frc.AHRS;
|
import com.kauailabs.navx.frc.AHRS;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj.SPI;
|
import edu.wpi.first.wpilibj.SPI;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
import frc.robot.constants.DrivetrainConstants;
|
import frc.robot.constants.DrivetrainConstants;
|
||||||
import frc.robot.utilities.MAXSwerveModule;
|
import frc.robot.utilities.MAXSwerveModule;
|
||||||
import frc.robot.utilities.SwerveUtils;
|
import frc.robot.utilities.SwerveUtils;
|
||||||
@ -91,6 +93,18 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
m_currentTranslationDir = 0.0;
|
m_currentTranslationDir = 0.0;
|
||||||
m_currentTranslationMag = 0.0;
|
m_currentTranslationMag = 0.0;
|
||||||
m_prevTime = WPIUtilJNI.now() * 1e-6;
|
m_prevTime = WPIUtilJNI.now() * 1e-6;
|
||||||
|
|
||||||
|
Shuffleboard.getTab("NavX")
|
||||||
|
.addDouble("YAW", m_gyro::getAngle)
|
||||||
|
.withPosition(0, 0)
|
||||||
|
.withSize(2, 1)
|
||||||
|
.withWidget(BuiltInWidgets.kTextView);
|
||||||
|
|
||||||
|
Shuffleboard.getTab("NavX")
|
||||||
|
.addDouble("Offset", m_gyro::getAngleAdjustment)
|
||||||
|
.withPosition(0, 1)
|
||||||
|
.withSize(2, 1)
|
||||||
|
.withWidget(BuiltInWidgets.kTextView);
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
|
Loading…
Reference in New Issue
Block a user