From d118bf6a8f9cc6f95c245dfaeed1cc3ce81a65d6 Mon Sep 17 00:00:00 2001 From: njoy3663 Date: Wed, 20 Nov 2024 19:09:55 -0800 Subject: [PATCH] arm sim --- .../com/frcteam3636/frc2024/subsystems/arm/ArmIO.kt | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/java/com/frcteam3636/frc2024/subsystems/arm/ArmIO.kt b/src/main/java/com/frcteam3636/frc2024/subsystems/arm/ArmIO.kt index 6e88d04..bdc5cd1 100644 --- a/src/main/java/com/frcteam3636/frc2024/subsystems/arm/ArmIO.kt +++ b/src/main/java/com/frcteam3636/frc2024/subsystems/arm/ArmIO.kt @@ -89,12 +89,12 @@ interface ArmIO{ inputs.absoluteEncoderPosition = Rotations.of(absoluteEncoder.absolutePosition) - inputs.leftPosition = Radians.of(leftMotor.position.value) - inputs.leftVelocity = RadiansPerSecond.of(leftMotor.velocity.value) + inputs.leftPosition = Rotations.of(leftMotor.position.value) + inputs.leftVelocity = RotationsPerSecond.of(leftMotor.velocity.value) - inputs.rightPosition = Radians.of(rightMotor.position.value) - inputs.rightVelocity = RadiansPerSecond.of(rightMotor.position.value) + inputs.rightPosition = Rotations.of(rightMotor.position.value) + inputs.rightVelocity = RotationsPerSecond.of(rightMotor.position.value) inputs.rightCurrent = Volts.of(leftMotor.motorVoltage.value) @@ -171,8 +171,8 @@ interface ArmIO{ class ArmIOSim : ArmIO { val armSim = SingleJointedArmSim( DCMotor.getKrakenX60(1), - 1.0, - 1.0, + 3.0, + 0.0301907551, 0.331414, -0.142921, 2.32814365359,