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

Commit

Permalink
Merge remote-tracking branch 'origin/main' into refactor/use-units
Browse files Browse the repository at this point in the history
  • Loading branch information
Gavin-Niederman committed Dec 11, 2024
2 parents 2ac9b30 + 17a3ab1 commit a6b369b
Show file tree
Hide file tree
Showing 6 changed files with 71 additions and 48 deletions.
3 changes: 3 additions & 0 deletions build.gradle.kts
Original file line number Diff line number Diff line change
Expand Up @@ -68,12 +68,15 @@ deploy {
// or from command line. If not found an exception will be thrown.
team = frc.getTeamOrDefault(3636)
debug = frc.getDebugOrDefault(false)


}

roborio.artifacts {
register<FRCJavaArtifact>("frcJava") {
jvmArgs.add("-ea") // Remove this flag during comp to disable asserts
setJarTask(tasks.jar)
dependsOn(tasks.assemble)
}

register<FileTreeArtifact>("frcStaticFileDeploy") {
Expand Down
72 changes: 37 additions & 35 deletions src/main/kotlin/com/frcteam3636/frc2024/Dashboard.kt
Original file line number Diff line number Diff line change
Expand Up @@ -30,64 +30,66 @@ object Dashboard {

tab.add("Swerve Drive", Drivetrain)!!
.withWidget(ElasticWidgets.SwerveDrive.widgetName)
.withSize(5, 3)
.withPosition(3, 0)
.withSize(4, 4)
.withPosition(6, 0)

tab.addNumber("Velocity, meters per second") {
Translation2d(
Drivetrain.measuredChassisSpeeds.vxMetersPerSecond,
Drivetrain.measuredChassisSpeeds.vyMetersPerSecond
).norm
}
.withWidget(ElasticWidgets.RadialGauge.widgetName)
// add a little extra to the max to improve visual spacing
.withProperties(
mapOf(
"min_value" to 0.0,
"max_value" to Drivetrain.Constants.FREE_SPEED.`in`(MetersPerSecond) + 4.0
)
)
.withSize(3, 3)
.withPosition(0, 0)
// tab.addNumber("Velocity, meters per second") {
// Translation2d(
// Drivetrain.measuredChassisSpeeds.vxMetersPerSecond,
// Drivetrain.measuredChassisSpeeds.vyMetersPerSecond
// ).norm
// }
// .withWidget(ElasticWidgets.RadialGauge.widgetName)
// // add a little extra to the max to improve visual spacing
// .withProperties(
// mapOf(
// "min_value" to 0.0,
// "max_value" to Drivetrain.Constants.FREE_SPEED.`in`(MetersPerSecond) + 4.0
// )
// )
// .withSize(3, 3)
// .withPosition(0, 0)

tab.addNumber("Match Time") { DriverStation.getMatchTime() }
.withWidget(ElasticWidgets.MatchTime.widgetName)
.withSize(4, 3)
.withPosition(4, 3)
.withSize(6, 4)
.withPosition(0, 4)

tab.add("Field", field)
.withWidget(BuiltInWidgets.kField)
.withSize(7, 4)
.withPosition(8, 0)
.withSize(12, 6)
.withPosition(12, 0)

tab.add("Auto Chooser", autoChooser)
.withWidget(BuiltInWidgets.kComboBoxChooser)
.withSize(2, 1)
.withPosition(9, 4)
.withSize(4, 2)
.withPosition(10, 6)

// Status Indicators
tab.addNumber("Battery Voltage") { RobotController.getBatteryVoltage() }
.withWidget(BuiltInWidgets.kVoltageView)
.withSize(3, 1)
.withPosition(0, 5)
.withSize(6, 2)
.withPosition(0, 2)

tab.addBoolean("NavX OK") { Diagnostics.latest.navXConnected }
.withPosition(3, 3)
.withPosition(10, 0)
.withSize(2, 1)
tab.addBoolean("Cameras OK") { Diagnostics.latest.navXConnected }
.withPosition(0, 3)
.withPosition(10, 1)
.withSize(2, 1)
tab.addBoolean("CAN Bus OK") { Diagnostics.latest.canStatus.transmitErrorCount == 0 && Diagnostics.latest.canStatus.receiveErrorCount == 0 }
.withPosition(0, 4)
.withPosition(10, 2)
.withSize(2, 1)
tab.addBoolean("TalonFX Devices OK") { Diagnostics.latest.errorStatusCodes.isEmpty() }
.withPosition(1, 3)
tab.addBoolean("TalonFX OK") { Diagnostics.latest.errorStatusCodes.isEmpty() }
.withPosition(10, 3)
.withSize(2, 1)

tab.addBoolean("Battery Full") { RobotController.getBatteryVoltage() >= 12.3 }
.withPosition(3, 5)
.withPosition(10, 4)
.withSize(2, 2)
tab.addNumber("CAN Bus Utilization") { Diagnostics.latest.canStatus.percentBusUtilization * 100.0 }
.withWidget(BuiltInWidgets.kNumberBar)
.withProperties(mapOf("min_value" to 0.0, "max_value" to 100.0))
.withPosition(2, 4)
.withSize(2, 1)
.withPosition(14, 6)
.withSize(4, 2)
}
}
15 changes: 15 additions & 0 deletions src/main/kotlin/com/frcteam3636/frc2024/Robot.kt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,9 @@ import com.frcteam3636.frc2024.subsystems.arm.Arm
import com.frcteam3636.frc2024.subsystems.drivetrain.Drivetrain
import com.frcteam3636.frc2024.subsystems.indexer.Indexer
import com.frcteam3636.frc2024.subsystems.intake.Intake
import com.frcteam3636.frc2024.utils.Elastic
import com.frcteam3636.frc2024.utils.ElasticNotification
import com.frcteam3636.frc2024.utils.NotificationLevel
import com.frcteam3636.version.BUILD_DATE
import com.frcteam3636.version.DIRTY
import com.frcteam3636.version.GIT_BRANCH
Expand All @@ -28,6 +31,9 @@ import org.littletonrobotics.junction.PatchedLoggedRobot
import org.littletonrobotics.junction.networktables.NT4Publisher
import org.littletonrobotics.junction.wpilog.WPILOGReader
import org.littletonrobotics.junction.wpilog.WPILOGWriter
import java.io.File
import kotlin.io.path.Path
import kotlin.io.path.exists


/**
Expand Down Expand Up @@ -85,6 +91,15 @@ object Robot : PatchedLoggedRobot() {

if (isReal()) {
Logger.addDataReceiver(WPILOGWriter()) // Log to a USB stick
if (!Path("/U").exists()) {
Elastic.sendAlert(
ElasticNotification(
"logging USB stick not plugged into radio",
"You gotta plug in a usb stick yo",
NotificationLevel.WARNING
)
)
}
Logger.addDataReceiver(NT4Publisher()) // Publish data to NetworkTables
// Enables power distribution logging
if (model == Model.COMPETITION) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -208,7 +208,7 @@ object Drivetrain : Subsystem, Sendable {
desiredChassisSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds(
translationInput.x * FREE_SPEED.baseUnitMagnitude() * TRANSLATION_SENSITIVITY,
translationInput.y * FREE_SPEED.baseUnitMagnitude() * TRANSLATION_SENSITIVITY,
rotationInput.x * TAU * ROTATION_SENSITIVITY,
-rotationInput.y * TAU * ROTATION_SENSITIVITY,
inputs.gyroRotation.toRotation2d()
)
}
Expand Down Expand Up @@ -279,10 +279,10 @@ object Drivetrain : Subsystem, Sendable {
internal object Constants {
// Translation/rotation coefficient for teleoperated driver controls
/** Unit: Percent of max robot speed */
const val TRANSLATION_SENSITIVITY = 1.0
const val TRANSLATION_SENSITIVITY = 0.1

/** Unit: Rotations per second */
const val ROTATION_SENSITIVITY = 1.25
const val ROTATION_SENSITIVITY = 0.4

private val WHEEL_BASE: Double = Units.inchesToMeters(30.0)
private val TRACK_WIDTH: Double = Units.inchesToMeters(28.0)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,14 @@ import org.littletonrobotics.junction.inputs.LoggableInputs
import com.frcteam3636.frc2024.CANSparkFlex
import com.frcteam3636.frc2024.REVMotorControllerId
import com.frcteam3636.frc2024.Robot
import com.frcteam3636.frc2024.subsystems.indexer.IndexerIOReal.Constants
import com.frcteam3636.frc2024.utils.LimelightHelpers
import com.frcteam3636.frc2024.utils.math.TAU
import com.revrobotics.CANSparkLowLevel
import edu.wpi.first.math.system.plant.DCMotor
import edu.wpi.first.units.Units.*
import edu.wpi.first.wpilibj.simulation.FlywheelSim
import org.littletonrobotics.junction.Logger
import org.team9432.annotation.Logged

enum class BalloonState {
Expand All @@ -36,9 +38,9 @@ interface IndexerIO {

class IndexerIOReal : IndexerIO{
companion object Constants {
const val RED_CLASS = "red"
const val BLUE_CLASS = "blue"
const val NONE_CLASS = "none"
const val RED_CLASS = "0 red"
const val BLUE_CLASS = "1 blue"
const val NONE_CLASS = ""
}

private var indexerMotor =
Expand All @@ -52,16 +54,18 @@ class IndexerIOReal : IndexerIO{
inputs.indexerCurrent = Amps.of(indexerMotor.outputCurrent)
inputs.position = Rotations.of(indexerMotor.encoder.position)

when (val colorClass = LimelightHelpers.getClassifierClass("limelight-sensor")) {
RED_CLASS -> inputs.balloonState = BalloonState.Red
BLUE_CLASS -> inputs.balloonState = BalloonState.Blue
NONE_CLASS -> inputs.balloonState = BalloonState.None
val colorClass = LimelightHelpers.getClassifierClass("limelight")
inputs.balloonState = when (colorClass) {
RED_CLASS -> BalloonState.Red
BLUE_CLASS -> BalloonState.Blue
NONE_CLASS -> BalloonState.None
else -> throw AssertionError("Unknown balloon class: $colorClass")
}
}

override fun setSpinSpeed(speed: Double) {
assert(speed in -1.0..1.0)
println("Speed: $speed")
indexerMotor.set(speed)
}
}
Expand Down Expand Up @@ -92,5 +96,4 @@ class IndexerIOPrototype: IndexerIO {

override fun setSpinSpeed(speed: Double) {
}

}
4 changes: 2 additions & 2 deletions src/main/kotlin/com/frcteam3636/frc2024/utils/Elastic.kt
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ data class ElasticNotification @JvmOverloads constructor(
@field:JsonProperty("title") var title: String,
@field:JsonProperty("description") var description: String,
@field:JsonProperty("level") var level: NotificationLevel = NotificationLevel.ERROR,
@field:JsonProperty("displayTime") var displayTimeMillis: Int = 3000,
@field:JsonProperty("displayTime") var displayTimeMillis: Int = 10000,
@field:JsonProperty("width") private val width: Double = 350.0,
@field:JsonProperty("height") private val height: Double = -1.0
) {
Expand All @@ -63,7 +63,7 @@ data class ElasticNotification @JvmOverloads constructor(
title,
description,
level,
3000,
10000,
width,
height
)
Expand Down

0 comments on commit a6b369b

Please sign in to comment.