Skip to content

Commit

Permalink
Small fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
Daniel1464 committed Oct 16, 2024
1 parent a4951fd commit 83007db
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 14 deletions.
6 changes: 3 additions & 3 deletions src/main/kotlin/frc/chargers/framework/HorseLog.kt
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,13 @@ import elastic.Elastic.ElasticNotification.NotificationLevel
* import frc.chargers.framework.HorseLog.logError
* import frc.chargers.framework.HorseLog // alternative
*
* log("Angle", 30.degrees) // will log as "Angle(SI Value)", 0.68(value in radians)
* log("AngleValue", 30.degrees) // will log as "AngleValue, 0.68"(value in radians)
* logError("Title", "Description")
* logNullableDouble("Hello", null)
* HorseLog.log("Angle", 30.degrees) // also valid
*/
@Suppress("unused")
object HorseLog { // inheritance doesnt do anything other than allowing for logQueuer access, as static inheritance doesnt exist in kotlin
object HorseLog {
/* Ported from DogLog */
fun log(key: String, value: Long) = DogLog.log(key, value)
fun log(key: String, value: Double) = DogLog.log(key, value)
Expand Down Expand Up @@ -107,7 +107,7 @@ object HorseLog { // inheritance doesnt do anything other than allowing for logQ
}

fun log(key: String, value: Int) = DogLog.log(key, value.toLong())
@JvmName("Log0") fun log(key: String, value: Quantity<*>) = DogLog.log("$key(SI Value)", value.siValue)
@JvmName("Log0") fun log(key: String, value: Quantity<*>) = DogLog.log(key, value.siValue)

fun logNullableInt(key: String, value: Int?) = logNullableImpl(key, value, ::log)
fun logNullableDouble(key: String, value: Double?) = logNullableImpl(key, value, ::log)
Expand Down
8 changes: 4 additions & 4 deletions src/main/kotlin/frc/chargers/framework/Tunable.kt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ import com.batterystaple.kmeasure.quantities.inUnit
import com.batterystaple.kmeasure.quantities.ofUnit
import com.pathplanner.lib.util.PIDConstants
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard
import edu.wpi.first.wpilibj2.command.InstantCommand
import kcommand.InstantCommand
import edu.wpi.first.wpilibj2.command.WaitCommand
import edu.wpi.first.wpilibj2.command.button.Trigger
import kotlin.reflect.KProperty
Expand Down Expand Up @@ -71,14 +71,14 @@ class Tunable<T>(
}
// waits to put the value to the dashboard so that SmartDashboard can initialize
WaitCommand(0.1)
.andThen(InstantCommand({ put(path, current) }))
.andThen(InstantCommand { put(path, current) })
.ignoringDisable(true)
.schedule()
Trigger { tuningMode && get(path, current) != current }
.whileTrue(InstantCommand({
.onTrue(InstantCommand {
current = get(path, current)
onChangeRunnables.forEach{ it(current) }
}))
}.ignoringDisable(true))
return this
}
operator fun getValue(thisRef: Any?, property: KProperty<*>): T = current
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,9 +66,8 @@ class SwerveModule(
couplingOffset -= constants.couplingRatio * (direction - 180.degrees)
log("CouplingOffset", couplingOffset)
}
if (turnEncoder != null) log("$name/absolutePosition", turnEncoder.angularPosition)
if (turnEncoder != null) log("$name/AbsoluteEncoderReading", turnEncoder.angularPosition)
log("$name/Direction", direction)
log("$name/AbsoluteEncoderReading", turnEncoder?.angularPosition ?: 0.degrees)
log("$name/DriveLinearVelocity", driveLinearVelocity)
log("$name/WheelTravel", wheelTravel)
log("$name/TurnMotorCurrent", turnMotor.statorCurrent)
Expand Down
3 changes: 0 additions & 3 deletions src/main/kotlin/frc/robot/rigatoni/CompetitionRobot.kt
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ import kcommand.setDefaultRunCommand
import frc.chargers.framework.ChargerRobot
import frc.chargers.framework.HorseLog
import frc.chargers.framework.Tunable
import frc.chargers.framework.tunable
import frc.chargers.hardware.sensors.imu.ChargerNavX
import frc.chargers.utils.squareMagnitude
import frc.chargers.wpilibextensions.distanceTo
Expand Down Expand Up @@ -56,8 +55,6 @@ class CompetitionRobot: ChargerRobot() {

private val autoChooser = SendableChooser<Command>()

val testTunable by tunable(2.0, "SomeValue").onChange { println("Hi!") }

init {
DriverStation.silenceJoystickConnectionWarning(true)
PortForwarder.add(5800, "photonvision.local", 5800)
Expand Down
9 changes: 7 additions & 2 deletions src/main/kotlin/frc/robot/rigatoni/subsystems/Pivot.kt
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,13 @@ class Pivot(disable: Boolean = false): SubsystemBase() {
positionPID = PIDConstants(7.0,0.0,0.001)
)
Trigger(DriverStation::isDisabled)
.onTrue(InstantCommand { setIdle(); motor.configure(brakeWhenIdle = false) })
.onFalse(InstantCommand { motor.configure(brakeWhenIdle = true) })
.onTrue(InstantCommand {
setIdle()
motor.configure(brakeWhenIdle = false)
}.ignoringDisable(true))
.onFalse(InstantCommand {
motor.configure(brakeWhenIdle = true)
}.ignoringDisable(true))
}

private val motionProfile: AngularMotionProfile? = AngularTrapezoidProfile(
Expand Down

0 comments on commit 83007db

Please sign in to comment.