From f480d6a502e804ed47229ec72babf5fc93bfd1c9 Mon Sep 17 00:00:00 2001 From: gaming <48131223+TheGamer1002@users.noreply.github.com> Date: Mon, 13 Jan 2025 16:20:33 -0500 Subject: [PATCH] chore(standards): remove Hungarian notation --- src/main/java/frc/robot/RobotContainer.kt | 4 +- src/main/java/frc/robot/Telemetry.kt | 58 ++--- .../frc/robot/generated/TunerConstants.kt | 198 +++++++++--------- .../subsystems/CommandSwerveDrivetrain.kt | 44 ++-- 4 files changed, 151 insertions(+), 153 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.kt b/src/main/java/frc/robot/RobotContainer.kt index 2e46e5d..6394fb0 100644 --- a/src/main/java/frc/robot/RobotContainer.kt +++ b/src/main/java/frc/robot/RobotContainer.kt @@ -10,10 +10,8 @@ import edu.wpi.first.wpilibj2.command.button.Trigger import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine import frc.robot.Constants.OperatorConstants import frc.robot.commands.Autos -import frc.robot.commands.ExampleCommand import frc.robot.generated.TunerConstants import frc.robot.subsystems.CommandSwerveDrivetrain -import frc.robot.subsystems.ExampleSubsystem /** * This class is where the bulk of the robot should be declared. Since Command-based is a @@ -29,7 +27,7 @@ import frc.robot.subsystems.ExampleSubsystem object RobotContainer { private val MaxSpeed = - TunerConstants.kSpeedAt12Volts.`in`(Units.MetersPerSecond) // kSpeedAt12Volts desired top speed + TunerConstants.speedAt12Volts.`in`(Units.MetersPerSecond) // kSpeedAt12Volts desired top speed private val MaxAngularRate = Units.RotationsPerSecond.of(0.75) .`in`(Units.RadiansPerSecond) // 3/4 of a rotation per second max angular velocity diff --git a/src/main/java/frc/robot/Telemetry.kt b/src/main/java/frc/robot/Telemetry.kt index d48f656..a714045 100755 --- a/src/main/java/frc/robot/Telemetry.kt +++ b/src/main/java/frc/robot/Telemetry.kt @@ -41,7 +41,7 @@ class Telemetry(private val MaxSpeed: Double) { private val fieldTypePub: StringPublisher = table.getStringTopic(".type").publish() /* Mechanisms to represent the swerve module states */ - private val m_moduleMechanisms = arrayOf( + private val moduleMechanisms = arrayOf( Mechanism2d(1.0, 1.0), Mechanism2d(1.0, 1.0), Mechanism2d(1.0, 1.0), @@ -49,32 +49,32 @@ class Telemetry(private val MaxSpeed: Double) { ) /* A direction and length changing ligament for speed representation */ - private val m_moduleSpeeds = arrayOf( - m_moduleMechanisms[0].getRoot("RootSpeed", 0.5, 0.5) + private val moduleSpeeds = arrayOf( + moduleMechanisms[0].getRoot("RootSpeed", 0.5, 0.5) .append(MechanismLigament2d("Speed", 0.5, 0.0)), - m_moduleMechanisms[1].getRoot("RootSpeed", 0.5, 0.5) + moduleMechanisms[1].getRoot("RootSpeed", 0.5, 0.5) .append(MechanismLigament2d("Speed", 0.5, 0.0)), - m_moduleMechanisms[2].getRoot("RootSpeed", 0.5, 0.5) + moduleMechanisms[2].getRoot("RootSpeed", 0.5, 0.5) .append(MechanismLigament2d("Speed", 0.5, 0.0)), - m_moduleMechanisms[3].getRoot("RootSpeed", 0.5, 0.5) + moduleMechanisms[3].getRoot("RootSpeed", 0.5, 0.5) .append(MechanismLigament2d("Speed", 0.5, 0.0)), ) /* A direction changing and length constant ligament for module direction */ - private val m_moduleDirections = arrayOf( - m_moduleMechanisms[0].getRoot("RootDirection", 0.5, 0.5) + private val moduleDirections = arrayOf( + moduleMechanisms[0].getRoot("RootDirection", 0.5, 0.5) .append(MechanismLigament2d("Direction", 0.1, 0.0, 0.0, Color8Bit(Color.kWhite))), - m_moduleMechanisms[1].getRoot("RootDirection", 0.5, 0.5) + moduleMechanisms[1].getRoot("RootDirection", 0.5, 0.5) .append(MechanismLigament2d("Direction", 0.1, 0.0, 0.0, Color8Bit(Color.kWhite))), - m_moduleMechanisms[2].getRoot("RootDirection", 0.5, 0.5) + moduleMechanisms[2].getRoot("RootDirection", 0.5, 0.5) .append(MechanismLigament2d("Direction", 0.1, 0.0, 0.0, Color8Bit(Color.kWhite))), - m_moduleMechanisms[3].getRoot("RootDirection", 0.5, 0.5) + moduleMechanisms[3].getRoot("RootDirection", 0.5, 0.5) .append(MechanismLigament2d("Direction", 0.1, 0.0, 0.0, Color8Bit(Color.kWhite))), ) - private val m_poseArray = DoubleArray(3) - private val m_moduleStatesArray = DoubleArray(8) - private val m_moduleTargetsArray = DoubleArray(8) + private val poseArray = DoubleArray(3) + private val moduleStatesArray = DoubleArray(8) + private val moduleTargetsArray = DoubleArray(8) /** * Construct a telemetry object, with the specified max speed of the robot @@ -97,33 +97,33 @@ class Telemetry(private val MaxSpeed: Double) { driveOdometryFrequency.set(1.0 / state.OdometryPeriod) /* Also write to log file */ - m_poseArray[0] = state.Pose.x - m_poseArray[1] = state.Pose.y - m_poseArray[2] = state.Pose.rotation.degrees + poseArray[0] = state.Pose.x + poseArray[1] = state.Pose.y + poseArray[2] = state.Pose.rotation.degrees for (i in 0..3) { - m_moduleStatesArray[i * 2 + 0] = state.ModuleStates[i].angle.radians - m_moduleStatesArray[i * 2 + 1] = state.ModuleStates[i].speedMetersPerSecond - m_moduleTargetsArray[i * 2 + 0] = state.ModuleTargets[i].angle.radians - m_moduleTargetsArray[i * 2 + 1] = state.ModuleTargets[i].speedMetersPerSecond + moduleStatesArray[i * 2 + 0] = state.ModuleStates[i].angle.radians + moduleStatesArray[i * 2 + 1] = state.ModuleStates[i].speedMetersPerSecond + moduleTargetsArray[i * 2 + 0] = state.ModuleTargets[i].angle.radians + moduleTargetsArray[i * 2 + 1] = state.ModuleTargets[i].speedMetersPerSecond } - SignalLogger.writeDoubleArray("DriveState/Pose", m_poseArray) - SignalLogger.writeDoubleArray("DriveState/ModuleStates", m_moduleStatesArray) - SignalLogger.writeDoubleArray("DriveState/ModuleTargets", m_moduleTargetsArray) + SignalLogger.writeDoubleArray("DriveState/Pose", poseArray) + SignalLogger.writeDoubleArray("DriveState/ModuleStates", moduleStatesArray) + SignalLogger.writeDoubleArray("DriveState/ModuleTargets", moduleTargetsArray) SignalLogger.writeDouble("DriveState/OdometryPeriod", state.OdometryPeriod, "seconds") /* Telemeterize the pose to a Field2d */ fieldTypePub.set("Field2d") - fieldPub.set(m_poseArray) + fieldPub.set(poseArray) /* Telemeterize the module states to a Mechanism2d */ for (i in 0..3) { - m_moduleSpeeds[i].setAngle(state.ModuleStates[i].angle) - m_moduleDirections[i].setAngle(state.ModuleStates[i].angle) - m_moduleSpeeds[i].length = + moduleSpeeds[i].setAngle(state.ModuleStates[i].angle) + moduleDirections[i].setAngle(state.ModuleStates[i].angle) + moduleSpeeds[i].length = state.ModuleStates[i].speedMetersPerSecond / (2 * MaxSpeed) - SmartDashboard.putData("Module $i", m_moduleMechanisms[i]) + SmartDashboard.putData("Module $i", moduleMechanisms[i]) } } } diff --git a/src/main/java/frc/robot/generated/TunerConstants.kt b/src/main/java/frc/robot/generated/TunerConstants.kt index 75882d8..e16419e 100755 --- a/src/main/java/frc/robot/generated/TunerConstants.kt +++ b/src/main/java/frc/robot/generated/TunerConstants.kt @@ -38,25 +38,25 @@ object TunerConstants { // The closed-loop output type to use for the steer motors; // This affects the PID/FF gains for the steer motors - private val kSteerClosedLoopOutput = SwerveModuleConstants.ClosedLoopOutputType.Voltage + private val steerClosedLoopOutput = SwerveModuleConstants.ClosedLoopOutputType.Voltage // The closed-loop output type to use for the drive motors; // This affects the PID/FF gains for the drive motors - private val kDriveClosedLoopOutput = SwerveModuleConstants.ClosedLoopOutputType.Voltage + private val driveClosedLoopOutput = SwerveModuleConstants.ClosedLoopOutputType.Voltage // The type of motor used for the drive motor - private val kDriveMotorType = DriveMotorArrangement.TalonFX_Integrated + private val driveMotorType = DriveMotorArrangement.TalonFX_Integrated // The type of motor used for the drive motor - private val kSteerMotorType = SteerMotorArrangement.TalonFX_Integrated + private val steerMotorType = SteerMotorArrangement.TalonFX_Integrated // The remote sensor feedback type to use for the steer motors; // When not Pro-licensed, FusedCANcoder/SyncCANcoder automatically fall back to RemoteCANcoder - private val kSteerFeedbackType = SwerveModuleConstants.SteerFeedbackType.FusedCANcoder + private val steerFeedbackType = SwerveModuleConstants.SteerFeedbackType.FusedCANcoder // The stator current at which the wheels start to slip; // This needs to be tuned to your individual robot - private val kSlipCurrent: Current = Units.Amps.of(40.0) + private val slipCurrent: Current = Units.Amps.of(40.0) // Initial configs for the drive and steer motors and the azimuth encoder; these cannot be null. // Some configs will be overwritten; check the `with*InitialConfigs()` API documentation. @@ -75,154 +75,154 @@ object TunerConstants { // CAN bus that the devices are located on; // All swerve devices must share the same CAN bus - val kCANBus: CANBus = CANBus("Drivebase", "./logs/example.hoot") + val canBus: CANBus = CANBus("Drivebase", "./logs/example.hoot") // Theoretical free speed (m/s) at 12 V applied output; // This needs to be tuned to your individual robot - val kSpeedAt12Volts: LinearVelocity = Units.FeetPerSecond.of(12.5) + val speedAt12Volts: LinearVelocity = Units.FeetPerSecond.of(12.5) // Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns; // This may need to be tuned to your individual robot - private const val kCoupleRatio = 3.5714285714285716 + private const val coupleRatio = 3.5714285714285716 - private const val kDriveGearRatio = 6.746031746031747 - private const val kSteerGearRatio = 21.428571428571427 + private const val driveGearRatio = 6.746031746031747 + private const val steerGearRatio = 21.428571428571427 private val kWheelRadius: Distance = Units.Inches.of(2.0) - private const val kInvertLeftSide = false - private const val kInvertRightSide = true + private const val invertLeftSide = false + private const val invertRightSide = true - private const val kPigeonId = 14 + private const val pigeonId = 14 // These are only used for simulation - private val kSteerInertia: MomentOfInertia = Units.KilogramSquareMeters.of(0.01) - private val kDriveInertia: MomentOfInertia = Units.KilogramSquareMeters.of(0.01) + private val steerInertia: MomentOfInertia = Units.KilogramSquareMeters.of(0.01) + private val driveInertia: MomentOfInertia = Units.KilogramSquareMeters.of(0.01) // Simulated voltage necessary to overcome friction - private val kSteerFrictionVoltage: Voltage = Units.Volts.of(0.2) - private val kDriveFrictionVoltage: Voltage = Units.Volts.of(0.2) + private val steerFrictionVoltage: Voltage = Units.Volts.of(0.2) + private val driveFrictionVoltage: Voltage = Units.Volts.of(0.2) - val DrivetrainConstants: SwerveDrivetrainConstants = SwerveDrivetrainConstants() - .withCANBusName(kCANBus.name) - .withPigeon2Id(kPigeonId) + private val DrivetrainConstants: SwerveDrivetrainConstants = SwerveDrivetrainConstants() + .withCANBusName(canBus.name) + .withPigeon2Id(pigeonId) .withPigeon2Configs(pigeonConfigs) private val ConstantCreator: SwerveModuleConstantsFactory = SwerveModuleConstantsFactory() - .withDriveMotorGearRatio(kDriveGearRatio) - .withSteerMotorGearRatio(kSteerGearRatio) - .withCouplingGearRatio(kCoupleRatio) + .withDriveMotorGearRatio(driveGearRatio) + .withSteerMotorGearRatio(steerGearRatio) + .withCouplingGearRatio(coupleRatio) .withWheelRadius(kWheelRadius) .withSteerMotorGains(steerGains) .withDriveMotorGains(driveGains) - .withSteerMotorClosedLoopOutput(kSteerClosedLoopOutput) - .withDriveMotorClosedLoopOutput(kDriveClosedLoopOutput) - .withSlipCurrent(kSlipCurrent) - .withSpeedAt12Volts(kSpeedAt12Volts) - .withDriveMotorType(kDriveMotorType) - .withSteerMotorType(kSteerMotorType) - .withFeedbackSource(kSteerFeedbackType) + .withSteerMotorClosedLoopOutput(steerClosedLoopOutput) + .withDriveMotorClosedLoopOutput(driveClosedLoopOutput) + .withSlipCurrent(slipCurrent) + .withSpeedAt12Volts(speedAt12Volts) + .withDriveMotorType(driveMotorType) + .withSteerMotorType(steerMotorType) + .withFeedbackSource(steerFeedbackType) .withDriveMotorInitialConfigs(driveInitialConfigs) .withSteerMotorInitialConfigs(steerInitialConfigs) .withEncoderInitialConfigs(encoderInitialConfigs) - .withSteerInertia(kSteerInertia) - .withDriveInertia(kDriveInertia) - .withSteerFrictionVoltage(kSteerFrictionVoltage) - .withDriveFrictionVoltage(kDriveFrictionVoltage) + .withSteerInertia(steerInertia) + .withDriveInertia(driveInertia) + .withSteerFrictionVoltage(steerFrictionVoltage) + .withDriveFrictionVoltage(driveFrictionVoltage) // Front Left - private const val kFrontLeftDriveMotorId = 4 - private const val kFrontLeftSteerMotorId = 6 - private const val kFrontLeftEncoderId = 5 - private val kFrontLeftEncoderOffset: Angle = Units.Rotations.of(-0.354736328125) - private const val kFrontLeftSteerMotorInverted = true - private const val kFrontLeftEncoderInverted = false + private const val frontLeftDriveMotorId = 4 + private const val frontLeftSteerMotorId = 6 + private const val frontLeftEncoderId = 5 + private val frontLeftEncoderOffset: Angle = Units.Rotations.of(-0.354736328125) + private const val frontLeftSteerMotorInverted = true + private const val frontLeftEncoderInverted = false - private val kFrontLeftXPos: Distance = Units.Inches.of(12.125) - private val kFrontLeftYPos: Distance = Units.Inches.of(12.125) + private val frontLeftXPos: Distance = Units.Inches.of(12.125) + private val frontLeftYPos: Distance = Units.Inches.of(12.125) // Front Right - private const val kFrontRightDriveMotorId = 1 - private const val kFrontRightSteerMotorId = 3 - private const val kFrontRightEncoderId = 2 - private val kFrontRightEncoderOffset: Angle = Units.Rotations.of(-0.321044921875) - private const val kFrontRightSteerMotorInverted = true - private const val kFrontRightEncoderInverted = false + private const val frontRightDriveMotorId = 1 + private const val frontRightSteerMotorId = 3 + private const val frontRightEncoderId = 2 + private val frontRightEncoderOffset: Angle = Units.Rotations.of(-0.321044921875) + private const val frontRightSteerMotorInverted = true + private const val frontRightEncoderInverted = false private val kFrontRightXPos: Distance = Units.Inches.of(12.125) private val kFrontRightYPos: Distance = Units.Inches.of(-12.125) // Back Left - private const val kBackLeftDriveMotorId = 7 - private const val kBackLeftSteerMotorId = 9 - private const val kBackLeftEncoderId = 8 - private val kBackLeftEncoderOffset: Angle = Units.Rotations.of(0.011474609375) - private const val kBackLeftSteerMotorInverted = true - private const val kBackLeftEncoderInverted = false + private const val backLeftDriveMotorId = 7 + private const val backLeftSteerMotorId = 9 + private const val backLeftEncoderId = 8 + private val backLeftEncoderOffset: Angle = Units.Rotations.of(0.011474609375) + private const val backLeftSteerMotorInverted = true + private const val backLeftEncoderInverted = false - private val kBackLeftXPos: Distance = Units.Inches.of(-12.125) - private val kBackLeftYPos: Distance = Units.Inches.of(12.125) + private val backLeftXPos: Distance = Units.Inches.of(-12.125) + private val backLeftYPos: Distance = Units.Inches.of(12.125) // Back Right - private const val kBackRightDriveMotorId = 10 - private const val kBackRightSteerMotorId = 12 - private const val kBackRightEncoderId = 11 - private val kBackRightEncoderOffset: Angle = Units.Rotations.of(0.31103515625) - private const val kBackRightSteerMotorInverted = true - private const val kBackRightEncoderInverted = false + private const val backRightDriveMotorId = 10 + private const val backRightSteerMotorId = 12 + private const val backRightEncoderId = 11 + private val backRightEncoderOffset: Angle = Units.Rotations.of(0.31103515625) + private const val backRightSteerMotorInverted = true + private const val backRightEncoderInverted = false - private val kBackRightXPos: Distance = Units.Inches.of(-12.125) - private val kBackRightYPos: Distance = Units.Inches.of(-12.125) + private val backRightXPos: Distance = Units.Inches.of(-12.125) + private val backRightYPos: Distance = Units.Inches.of(-12.125) val FrontLeft: SwerveModuleConstants = ConstantCreator.createModuleConstants( - kFrontLeftSteerMotorId, - kFrontLeftDriveMotorId, - kFrontLeftEncoderId, - kFrontLeftEncoderOffset, - kFrontLeftXPos, - kFrontLeftYPos, - kInvertLeftSide, - kFrontLeftSteerMotorInverted, - kFrontLeftEncoderInverted + frontLeftSteerMotorId, + frontLeftDriveMotorId, + frontLeftEncoderId, + frontLeftEncoderOffset, + frontLeftXPos, + frontLeftYPos, + invertLeftSide, + frontLeftSteerMotorInverted, + frontLeftEncoderInverted ) val FrontRight: SwerveModuleConstants = ConstantCreator.createModuleConstants( - kFrontRightSteerMotorId, - kFrontRightDriveMotorId, - kFrontRightEncoderId, - kFrontRightEncoderOffset, + frontRightSteerMotorId, + frontRightDriveMotorId, + frontRightEncoderId, + frontRightEncoderOffset, kFrontRightXPos, kFrontRightYPos, - kInvertRightSide, - kFrontRightSteerMotorInverted, - kFrontRightEncoderInverted + invertRightSide, + frontRightSteerMotorInverted, + frontRightEncoderInverted ) val BackLeft: SwerveModuleConstants = ConstantCreator.createModuleConstants( - kBackLeftSteerMotorId, - kBackLeftDriveMotorId, - kBackLeftEncoderId, - kBackLeftEncoderOffset, - kBackLeftXPos, - kBackLeftYPos, - kInvertLeftSide, - kBackLeftSteerMotorInverted, - kBackLeftEncoderInverted + backLeftSteerMotorId, + backLeftDriveMotorId, + backLeftEncoderId, + backLeftEncoderOffset, + backLeftXPos, + backLeftYPos, + invertLeftSide, + backLeftSteerMotorInverted, + backLeftEncoderInverted ) val BackRight: SwerveModuleConstants = ConstantCreator.createModuleConstants( - kBackRightSteerMotorId, - kBackRightDriveMotorId, - kBackRightEncoderId, - kBackRightEncoderOffset, - kBackRightXPos, - kBackRightYPos, - kInvertRightSide, - kBackRightSteerMotorInverted, - kBackRightEncoderInverted + backRightSteerMotorId, + backRightDriveMotorId, + backRightEncoderId, + backRightEncoderOffset, + backRightXPos, + backRightYPos, + invertRightSide, + backRightSteerMotorInverted, + backRightEncoderInverted ) /** diff --git a/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.kt b/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.kt index 2edc39d..3dcdfb3 100644 --- a/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.kt +++ b/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.kt @@ -28,19 +28,19 @@ import java.util.function.Supplier * Subsystem so it can easily be used in command-based projects. */ class CommandSwerveDrivetrain : TunerSwerveDrivetrain, Subsystem { - private var m_simNotifier: Notifier? = null - private var m_lastSimTime = 0.0 + private var simNotifier: Notifier? = null + private var lastSimTime = 0.0 /* Keep track if we've ever applied the operator perspective before or not */ - private var m_hasAppliedOperatorPerspective = false + private var hasAppliedOperatorPerspective = false /* Swerve requests to apply during SysId characterization */ - private val m_translationCharacterization = SwerveRequest.SysIdSwerveTranslation() - private val m_steerCharacterization = SwerveRequest.SysIdSwerveSteerGains() - private val m_rotationCharacterization = SwerveRequest.SysIdSwerveRotation() + private val translationCharacterization = SwerveRequest.SysIdSwerveTranslation() + private val steerCharacterization = SwerveRequest.SysIdSwerveSteerGains() + private val rotationCharacterization = SwerveRequest.SysIdSwerveRotation() /* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */ - private val m_sysIdRoutineTranslation = SysIdRoutine( + private val sysIdRoutineTranslation = SysIdRoutine( SysIdRoutine.Config( null, // Use default ramp rate (1 V/s) Units.Volts.of(4.0), // Reduce dynamic step voltage to 4 V to prevent brownout @@ -54,14 +54,14 @@ class CommandSwerveDrivetrain : TunerSwerveDrivetrain, Subsystem { ) }, Mechanism( - { output: Voltage? -> setControl(m_translationCharacterization.withVolts(output)) }, + { output: Voltage? -> setControl(translationCharacterization.withVolts(output)) }, null, this ) ) /* SysId routine for characterizing steer. This is used to find PID gains for the steer motors. */ - private val m_sysIdRoutineSteer = SysIdRoutine( + private val sysIdRoutineSteer = SysIdRoutine( SysIdRoutine.Config( null, // Use default ramp rate (1 V/s) Units.Volts.of(7.0), // Use dynamic voltage of 7 V @@ -75,7 +75,7 @@ class CommandSwerveDrivetrain : TunerSwerveDrivetrain, Subsystem { ) }, Mechanism( - { volts: Voltage? -> setControl(m_steerCharacterization.withVolts(volts)) }, + { volts: Voltage? -> setControl(steerCharacterization.withVolts(volts)) }, null, this ) @@ -86,7 +86,7 @@ class CommandSwerveDrivetrain : TunerSwerveDrivetrain, Subsystem { * This is used to find PID gains for the FieldCentricFacingAngle HeadingController. * See the documentation of SwerveRequest.SysIdSwerveRotation for info on importing the log to SysId. */ - private val m_sysIdRoutineRotation = SysIdRoutine( + private val sysIdRoutineRotation = SysIdRoutine( SysIdRoutine.Config( /* This is in radians per secondĀ², but SysId only supports "volts per second" */ Units.Volts.of(Math.PI / 6) .per(Units.Second), /* This is in radians per second, but SysId only supports "volts" */ @@ -103,7 +103,7 @@ class CommandSwerveDrivetrain : TunerSwerveDrivetrain, Subsystem { Mechanism( { output: Voltage -> /* output is actually radians per second, but SysId only supports "volts" */ - setControl(m_rotationCharacterization.withRotationalRate(output.`in`(Units.Volts))) + setControl(rotationCharacterization.withRotationalRate(output.`in`(Units.Volts))) /* also log the requested output for SysId */ SignalLogger.writeDouble( "Rotational_Rate", @@ -116,7 +116,7 @@ class CommandSwerveDrivetrain : TunerSwerveDrivetrain, Subsystem { ) /* The SysId routine to test */ - private val m_sysIdRoutineToApply = m_sysIdRoutineTranslation + private val sysIdRoutineToApply = sysIdRoutineTranslation /** * Constructs a CTRE SwerveDrivetrain using the specified constants. @@ -218,7 +218,7 @@ class CommandSwerveDrivetrain : TunerSwerveDrivetrain, Subsystem { * @return Command to run */ fun sysIdQuasistatic(direction: SysIdRoutine.Direction?): Command { - return m_sysIdRoutineToApply.quasistatic(direction) + return sysIdRoutineToApply.quasistatic(direction) } /** @@ -229,7 +229,7 @@ class CommandSwerveDrivetrain : TunerSwerveDrivetrain, Subsystem { * @return Command to run */ fun sysIdDynamic(direction: SysIdRoutine.Direction?): Command { - return m_sysIdRoutineToApply.dynamic(direction) + return sysIdRoutineToApply.dynamic(direction) } override fun periodic() { @@ -240,7 +240,7 @@ class CommandSwerveDrivetrain : TunerSwerveDrivetrain, Subsystem { * Otherwise, only check and apply the operator perspective if the DS is disabled. * This ensures driving behavior doesn't change until an explicit disable event occurs during testing. */ - if (!m_hasAppliedOperatorPerspective || DriverStation.isDisabled()) { + if (!hasAppliedOperatorPerspective || DriverStation.isDisabled()) { DriverStation.getAlliance().ifPresent { allianceColor: Alliance -> setOperatorPerspectiveForward( if (allianceColor == Alliance.Red) @@ -248,24 +248,24 @@ class CommandSwerveDrivetrain : TunerSwerveDrivetrain, Subsystem { else kBlueAlliancePerspectiveRotation ) - m_hasAppliedOperatorPerspective = true + hasAppliedOperatorPerspective = true } } } private fun startSimThread() { - m_lastSimTime = Utils.getCurrentTimeSeconds() + lastSimTime = Utils.getCurrentTimeSeconds() /* Run simulation at a faster rate so PID gains behave more reasonably */ - m_simNotifier = Notifier { + simNotifier = Notifier { val currentTime = Utils.getCurrentTimeSeconds() - val deltaTime = currentTime - m_lastSimTime - m_lastSimTime = currentTime + val deltaTime = currentTime - lastSimTime + lastSimTime = currentTime /* use the measured time delta, get battery voltage from WPILib */ updateSimState(deltaTime, RobotController.getBatteryVoltage()) } - m_simNotifier!!.startPeriodic(kSimLoopPeriod) + simNotifier!!.startPeriodic(kSimLoopPeriod) } companion object {