Skip to content
This repository has been archived by the owner on Dec 19, 2024. It is now read-only.

Commit

Permalink
Changed arm to update the relative encoders to the absolute encoders …
Browse files Browse the repository at this point in the history
…periodically
  • Loading branch information
Taimorioka committed Dec 4, 2024
1 parent 8b0d0ce commit bcf53ed
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 6 deletions.
15 changes: 11 additions & 4 deletions src/main/kotlin/com/frcteam3636/frc2024/subsystems/arm/Arm.kt
Original file line number Diff line number Diff line change
Expand Up @@ -2,20 +2,20 @@ package com.frcteam3636.frc2024.subsystems.arm

import com.ctre.phoenix6.SignalLogger
import com.frcteam3636.frc2024.Robot
import com.frcteam3636.frc2024.subsystems.indexer.IndexerIOPrototype
import com.frcteam3636.frc2024.subsystems.indexer.IndexerIOReal
import com.frcteam3636.frc2024.subsystems.indexer.IndexerIOSim
import edu.wpi.first.units.Angle
import edu.wpi.first.units.Measure
import edu.wpi.first.units.Units.Degrees
import edu.wpi.first.units.Units.Volts
import edu.wpi.first.wpilibj.Timer
import edu.wpi.first.wpilibj2.command.Subsystem
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Mechanism
import org.littletonrobotics.junction.Logger


private const val SECONDS_BETWEEN_ARM_UPDATES = 0.5

object Arm : Subsystem {
private var io: ArmIO = when (Robot.model) {
Robot.Model.SIMULATION -> ArmIOSim()
Expand All @@ -34,10 +34,17 @@ object Arm : Subsystem {
Mechanism(io::setVoltage, null, this)
)

private var timer = Timer().apply {
start()
}

override fun periodic() {
io.updateInputs(inputs)

Logger.processInputs("/Arm", inputs)
if (timer.advanceIfElapsed(SECONDS_BETWEEN_ARM_UPDATES) && inputs.absoluteEncoderConnected){
io.updatePosition(inputs.absoluteEncoderPosition)
}

}

fun moveToPosition(position: Position) =
Expand Down
18 changes: 16 additions & 2 deletions src/main/kotlin/com/frcteam3636/frc2024/subsystems/arm/ArmIO.kt
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@ import edu.wpi.first.units.Units.*
import edu.wpi.first.units.Voltage
import edu.wpi.first.wpilibj.DigitalInput
import edu.wpi.first.wpilibj.DutyCycleEncoder
import edu.wpi.first.wpilibj.simulation.FlywheelSim
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim
import org.littletonrobotics.junction.LogTable
import org.littletonrobotics.junction.Logger
Expand Down Expand Up @@ -72,9 +71,12 @@ interface ArmIO{

fun pivotToPosition(position: Measure<Angle>)

fun setVoltage(volts: Measure<Voltage>)
fun setVoltage(volts: Measure<Voltage>)

fun updatePosition(position: Measure<Angle>)
}


class ArmIOReal: ArmIO{

private val leftMotor = TalonFX(CTREMotorControllerId.LeftArmMotor)
Expand Down Expand Up @@ -102,6 +104,11 @@ interface ArmIO{
rightMotor.setPosition(inputs.absoluteEncoderPosition.`in`(Rotations))
}

override fun updatePosition(position: Measure<Angle>) {
leftMotor.setPosition(position.`in`(Rotations))
rightMotor.setPosition(position.`in`(Rotations))
}

override fun pivotToPosition(position: Measure<Angle>) {
Logger.recordOutput("Shooter/Pivot/Position Setpoint", position)

Expand Down Expand Up @@ -198,6 +205,10 @@ interface ArmIO{
override fun setVoltage(volts: Measure<Voltage>) {
armSim.setInputVoltage(volts.`in`(Volts))
}

override fun updatePosition(position: Measure<Angle>) {
// no drifting in sim so no need to update
}
}

class ArmIOPrototype: ArmIO {
Expand All @@ -210,4 +221,7 @@ interface ArmIO{

override fun setVoltage(volts: Measure<Voltage>) {
}

override fun updatePosition(position: Measure<Angle>) {
}
}

0 comments on commit bcf53ed

Please sign in to comment.