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

Commit

Permalink
added arm sim, got around issue w/ advatagekit not detecting wpilib b…
Browse files Browse the repository at this point in the history
…y changing a file that probably shouldn't be changed.
  • Loading branch information
Taimorioka committed Dec 5, 2024
1 parent ed97897 commit d1d68e4
Show file tree
Hide file tree
Showing 9 changed files with 228 additions and 65 deletions.
7 changes: 5 additions & 2 deletions src/main/kotlin/com/frcteam3636/frc2024/CAN.kt
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package com.frcteam3636.frc2024

import com.ctre.phoenix6.hardware.Pigeon2
import com.ctre.phoenix6.hardware.TalonFX
import com.revrobotics.CANSparkFlex
import com.revrobotics.CANSparkLowLevel
Expand Down Expand Up @@ -29,13 +30,15 @@ fun CANSparkMax(id: REVMotorControllerId, type: CANSparkLowLevel.MotorType) =
fun CANSparkFlex(id: REVMotorControllerId, type: CANSparkLowLevel.MotorType) =
CANSparkFlex(id.num, type)

enum class CTREMotorControllerId(val num: Int, val bus: String) {
enum class CTREDeviceId(val num: Int, val bus: String) {
FrontLeftDrivingMotor(1, "*"),
BackLeftDrivingMotor(2, "*"),
BackRightDrivingMotor(3, "*"),
FrontRightDrivingMotor(4, "*"),
RightArmMotor(10, "*"),
LeftArmMotor(11, "*"),
PigeonGyro(20, "*"),
}

fun TalonFX(id: CTREMotorControllerId) = TalonFX(id.num, id.bus)
fun TalonFX(id: CTREDeviceId) = TalonFX(id.num, id.bus)
fun Pigeon2(id: CTREDeviceId) = Pigeon2(id.num, id.bus)
136 changes: 136 additions & 0 deletions src/main/kotlin/com/frcteam3636/frc2024/LoggedRobot.kt
Original file line number Diff line number Diff line change
@@ -0,0 +1,136 @@
package org.littletonrobotics.junction

import edu.wpi.first.hal.DriverStationJNI
import edu.wpi.first.hal.FRCNetComm
import edu.wpi.first.hal.HAL
import edu.wpi.first.hal.NotifierJNI
import edu.wpi.first.wpilibj.IterativeRobotBase
import org.littletonrobotics.junction.AutoLogOutputManager
import org.littletonrobotics.junction.CheckInstall
import org.littletonrobotics.junction.Logger
import java.lang.management.GarbageCollectorMXBean
import java.lang.management.ManagementFactory


/**
* LoggedRobot implements the IterativeRobotBase robot program framework.
*
*
*
* The LoggedRobot class is intended to be subclassed by a user creating a robot
* program, and will call all required AdvantageKit periodic methods.
*
*
*
* periodic() functions from the base class are called on an interval by a
* Notifier instance.
*/
open class MyLoggedRobot protected constructor(period: Double = defaultPeriodSecs) :
IterativeRobotBase(period) {
private val notifier = NotifierJNI.initializeNotifier()
private val periodUs = (period * 1000000).toLong()
private var nextCycleUs: Long = 0
private val gcStatsCollector = GcStatsCollector()

private var useTiming = true

/**
* Constructor for LoggedRobot.
*
* @param period Period in seconds.
*/
/** Constructor for LoggedRobot. */
init {
NotifierJNI.setNotifierName(notifier, "LoggedRobot")

HAL.report(FRCNetComm.tResourceType.kResourceType_Framework, FRCNetComm.tInstances.kFramework_AdvantageKit)
}

protected fun finalize() {
NotifierJNI.stopNotifier(notifier)
NotifierJNI.cleanNotifier(notifier)
}

/** Provide an alternate "main loop" via startCompetition(). */
override fun startCompetition() {
// Robot init methods
val initStart = Logger.getRealTimestamp()
robotInit()
if (isSimulation()) {
simulationInit()
}
val initEnd = Logger.getRealTimestamp()

// Register auto logged outputs
AutoLogOutputManager.registerFields(this)

// Save data from init cycle
Logger.periodicAfterUser(initEnd - initStart, 0)

// Tell the DS that the robot is ready to be enabled
println("********** Robot program startup complete **********")
DriverStationJNI.observeUserProgramStarting()

// Loop forever, calling the appropriate mode-dependent function
while (true) {
if (useTiming) {
val currentTimeUs = Logger.getRealTimestamp()
if (nextCycleUs < currentTimeUs) {
// Loop overrun, start next cycle immediately
nextCycleUs = currentTimeUs
} else {
// Wait before next cycle
NotifierJNI.updateNotifierAlarm(notifier, nextCycleUs)
NotifierJNI.waitForNotifierAlarm(notifier)
}
nextCycleUs += periodUs
}

val periodicBeforeStart = Logger.getRealTimestamp()
Logger.periodicBeforeUser()
val userCodeStart = Logger.getRealTimestamp()
loopFunc()
val userCodeEnd = Logger.getRealTimestamp()

gcStatsCollector.update()
Logger.periodicAfterUser(userCodeEnd - userCodeStart, userCodeStart - periodicBeforeStart)
}
}

/** Ends the main loop in startCompetition(). */
override fun endCompetition() {
NotifierJNI.stopNotifier(notifier)
}

/** Sets whether to use standard timing or run as fast as possible. */
fun setUseTiming(useTiming: Boolean) {
this.useTiming = useTiming
}

private class GcStatsCollector {
private val gcBeans: List<GarbageCollectorMXBean> = ManagementFactory.getGarbageCollectorMXBeans()
private val lastTimes = LongArray(gcBeans.size)
private val lastCounts = LongArray(gcBeans.size)

fun update() {
var accumTime: Long = 0
var accumCounts: Long = 0
for (i in gcBeans.indices) {
val gcTime = gcBeans[i].collectionTime
val gcCount = gcBeans[i].collectionCount
accumTime += gcTime - lastTimes[i]
accumCounts += gcCount - lastCounts[i]

lastTimes[i] = gcTime
lastCounts[i] = gcCount
}

Logger.recordOutput("LoggedRobot/GCTimeMS", accumTime.toDouble())
Logger.recordOutput("LoggedRobot/GCCounts", accumCounts.toDouble())
}
}

companion object {
const val defaultPeriodSecs: Double = 0.02
}
}
5 changes: 3 additions & 2 deletions src/main/kotlin/com/frcteam3636/frc2024/Robot.kt
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@ import edu.wpi.first.wpilibj2.command.button.CommandXboxController
import edu.wpi.first.wpilibj2.command.button.JoystickButton
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine
import org.littletonrobotics.junction.LogFileUtil
import org.littletonrobotics.junction.LoggedRobot
import org.littletonrobotics.junction.Logger
import org.littletonrobotics.junction.MyLoggedRobot
import org.littletonrobotics.junction.networktables.NT4Publisher
import org.littletonrobotics.junction.wpilog.WPILOGReader
import org.littletonrobotics.junction.wpilog.WPILOGWriter
Expand All @@ -41,7 +41,7 @@ import org.littletonrobotics.junction.wpilog.WPILOGWriter
* update the `Main.kt` file in the project. (If you use the IDE's Rename or Move refactorings when
* renaming the object or package, it will get changed everywhere.)
*/
object Robot : LoggedRobot() {
object Robot : MyLoggedRobot() {
private val controller = CommandXboxController(2)
private val joystickLeft = Joystick(0)
private val joystickRight = Joystick(1)
Expand Down Expand Up @@ -124,6 +124,7 @@ object Robot : LoggedRobot() {
Drivetrain.register()
Indexer.register()
Intake.register()
Arm.register()
}

/** Expose commands for autonomous routines to use and display an auto picker in Shuffleboard. */
Expand Down
25 changes: 24 additions & 1 deletion src/main/kotlin/com/frcteam3636/frc2024/subsystems/arm/Arm.kt
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,25 @@ package com.frcteam3636.frc2024.subsystems.arm

import com.ctre.phoenix6.SignalLogger
import com.frcteam3636.frc2024.Robot
import com.frcteam3636.frc2024.subsystems.intake.Intake
import com.frcteam3636.frc2024.subsystems.intake.Intake.indexerAngleLigament
import com.frcteam3636.frc2024.subsystems.intake.Intake.intakeAngleLigament
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.wpilibj.smartdashboard.Mechanism2d
import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d
import edu.wpi.first.wpilibj.util.Color
import edu.wpi.first.wpilibj.util.Color8Bit
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
import kotlin.math.cos
import kotlin.math.sin


private const val SECONDS_BETWEEN_ARM_UPDATES = 0.5
Expand All @@ -23,7 +32,17 @@ object Arm : Subsystem {
Robot.Model.PROTOTYPE -> ArmIOPrototype()
}

var inputs = ArmIO.ArmInputs()
var inputs = LoggedArmInputs()
var mechanism = Mechanism2d(200.0, 200.0)
var armAngleLigament = MechanismLigament2d("Arm Ligament", 50.0, 90.0, 5.0, Color8Bit(Color.kGreen))
var armWristAngleLigament = MechanismLigament2d("Arm Wrist Ligament", 20.0, 90.0, 5.0, Color8Bit(Color.kGreen))

init {
mechanism.getRoot("Arm", 100.0, 100.0).apply{
append(armAngleLigament)
}
armAngleLigament.append(armWristAngleLigament)
}

private var sysID = SysIdRoutine(
SysIdRoutine.Config(
Expand All @@ -41,9 +60,13 @@ object Arm : Subsystem {
override fun periodic() {
io.updateInputs(inputs)
Logger.processInputs("/Arm", inputs)
armAngleLigament.angle = inputs.position.`in`(Degrees)
armWristAngleLigament.angle = 90.0 - inputs.position.`in`(Degrees)

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

}

Expand Down
76 changes: 26 additions & 50 deletions src/main/kotlin/com/frcteam3636/frc2024/subsystems/arm/ArmIO.kt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ import com.ctre.phoenix6.controls.VoltageOut
import com.ctre.phoenix6.signals.GravityTypeValue
import com.ctre.phoenix6.signals.InvertedValue
import com.ctre.phoenix6.signals.NeutralModeValue
import com.frcteam3636.frc2024.CTREMotorControllerId
import com.frcteam3636.frc2024.CTREDeviceId
import com.frcteam3636.frc2024.Robot
import com.frcteam3636.frc2024.TalonFX
import com.frcteam3636.frc2024.utils.math.*
Expand All @@ -20,52 +20,26 @@ import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim
import org.littletonrobotics.junction.LogTable
import org.littletonrobotics.junction.Logger
import org.littletonrobotics.junction.inputs.LoggableInputs
import org.team9432.annotation.Logged

@Logged
open class ArmInputs {
var rightPosition = Radians.zero()!!
var leftPosition = Radians.zero()!!
var position = Radians.zero()!!

interface ArmIO{
class ArmInputs : LoggableInputs {

var rightPosition = Radians.zero()!!
var leftPosition = Radians.zero()!!
var position = Radians.zero()!!

var absoluteEncoderPosition = Radians.zero()!!

var rightCurrent = Volts.zero()!!
var leftCurrent = Volts.zero()!!
var absoluteEncoderPosition = Radians.zero()!!

var rightVelocity = RadiansPerSecond.zero()!!
var leftVelocity = RadiansPerSecond.zero()!!
var rightCurrent = Volts.zero()!!
var leftCurrent = Volts.zero()!!

var absoluteEncoderConnected = false
var rightVelocity = RadiansPerSecond.zero()!!
var leftVelocity = RadiansPerSecond.zero()!!

var absoluteEncoderConnected = false
}

override fun toLog(table: LogTable) {
table.put("Right Arm Motor Position", rightPosition)
table.put("Left Arm Motor Position", leftPosition)

table.put("Right Arm Motor Current", rightCurrent)
table.put("Left Arm Motor Current", leftCurrent)

table.put("Right Arm Motor Velocity", rightVelocity)
table.put("Left Arm Motor Velocity", leftVelocity)

table.put("Absolute Encoder Connected",absoluteEncoderConnected )
}

override fun fromLog(table: LogTable) {
rightPosition = table.get("Right Arm Motor Position", rightPosition)
leftPosition = table.get("Left Arm Motor Position", leftPosition)

rightCurrent = table.get("Right Arm Motor Current", rightCurrent)
leftCurrent = table.get("Left Arm Motor Current", leftCurrent)

rightVelocity = table.get("Right Arm Motor Velocity", rightVelocity)
leftVelocity = table.get("Left Arm Motor Velocity", leftVelocity)

absoluteEncoderConnected = table.get("Absolute Encoder Connected", absoluteEncoderConnected)
}
}
interface ArmIO{

fun updateInputs(inputs: ArmInputs)

Expand All @@ -79,13 +53,13 @@ interface ArmIO{

class ArmIOReal: ArmIO{

private val leftMotor = TalonFX(CTREMotorControllerId.LeftArmMotor)
private val leftMotor = TalonFX(CTREDeviceId.LeftArmMotor)

private val rightMotor = TalonFX(CTREMotorControllerId.RightArmMotor)
private val rightMotor = TalonFX(CTREDeviceId.RightArmMotor)

private val absoluteEncoder = DutyCycleEncoder(DigitalInput(8))

override fun updateInputs(inputs: ArmIO.ArmInputs) {
override fun updateInputs(inputs: ArmInputs) {
inputs.position = Rotations.of(absoluteEncoder.absolutePosition)
inputs.absoluteEncoderConnected = absoluteEncoder.isConnected

Expand Down Expand Up @@ -179,23 +153,24 @@ interface ArmIO{
val armSim = SingleJointedArmSim(
DCMotor.getKrakenX60(1),
3.0,
0.0301907551,
0.244,
0.331414,
-0.142921,
2.32814365359,
true,
-0.142921
)

val pidController = PIDController(ArmIOReal.PID_GAINS)
// val pidController = PIDController(ArmIOReal.PID_GAINS)
var setPoint = 0.0

override fun updateInputs(inputs: ArmIO.ArmInputs) {
override fun updateInputs(inputs: ArmInputs) {
armSim.update(Robot.period)
inputs.rightVelocity = RadiansPerSecond.of(armSim.velocityRadPerSec)
inputs.leftVelocity = RadiansPerSecond.of(armSim.velocityRadPerSec)
val pidVoltage = pidController.calculate(inputs.position.`in`(Radians),setPoint)
armSim.setInputVoltage(pidVoltage)
inputs.position = Radians.of(armSim.angleRads)
// val pidVoltage = pidController.calculate(inputs.position.`in`(Radians),setPoint)
// armSim.setInputVoltage(pidVoltage)
}

override fun pivotToPosition(position: Measure<Angle>) {
Expand All @@ -204,6 +179,7 @@ interface ArmIO{

override fun setVoltage(volts: Measure<Voltage>) {
armSim.setInputVoltage(volts.`in`(Volts))
Logger.recordOutput("/Arm/OutVolt", volts)
}

override fun updatePosition(position: Measure<Angle>) {
Expand All @@ -213,7 +189,7 @@ interface ArmIO{

class ArmIOPrototype: ArmIO {
//placeholder
override fun updateInputs(inputs: ArmIO.ArmInputs) {
override fun updateInputs(inputs: ArmInputs) {
}

override fun pivotToPosition(position: Measure<Angle>) {
Expand Down
Loading

0 comments on commit d1d68e4

Please sign in to comment.