Skip to content

Commit

Permalink
fix(sim): it seems not to like dashboard entries when under a simulation
Browse files Browse the repository at this point in the history
  • Loading branch information
TheGamer1002 committed Oct 25, 2024
1 parent 4920ceb commit d16b0dc
Show file tree
Hide file tree
Showing 4 changed files with 165 additions and 12 deletions.
1 change: 1 addition & 0 deletions networktables.json
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
[]
97 changes: 97 additions & 0 deletions simgui-ds.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
{
"keyboardJoysticks": [
{
"axisConfig": [
{
"decKey": 65,
"incKey": 68
},
{
"decKey": 87,
"incKey": 83
},
{
"decKey": 69,
"decayRate": 0.0,
"incKey": 82,
"keyRate": 0.009999999776482582
}
],
"axisCount": 3,
"buttonCount": 4,
"buttonKeys": [
90,
88,
67,
86
],
"povConfig": [
{
"key0": 328,
"key135": 323,
"key180": 322,
"key225": 321,
"key270": 324,
"key315": 327,
"key45": 329,
"key90": 326
}
],
"povCount": 1
},
{
"axisConfig": [
{
"decKey": 74,
"incKey": 76
},
{
"decKey": 73,
"incKey": 75
}
],
"axisCount": 2,
"buttonCount": 4,
"buttonKeys": [
77,
44,
46,
47
],
"povCount": 0
},
{
"axisConfig": [
{
"decKey": 263,
"incKey": 262
},
{
"decKey": 265,
"incKey": 264
}
],
"axisCount": 2,
"buttonCount": 6,
"buttonKeys": [
260,
268,
266,
261,
269,
267
],
"povCount": 0
},
{
"axisCount": 0,
"buttonCount": 0,
"povCount": 0
}
],
"robotJoysticks": [
{
"guid": "Keyboard0"
}
]
}
28 changes: 28 additions & 0 deletions simgui.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
{
"NTProvider": {
"types": {
"/FMSInfo": "FMSInfo",
"/Pose": "Field2d",
"/SmartDashboard/Auto Chooser": "String Chooser",
"/SmartDashboard/Control Chooser": "String Chooser",
"/SmartDashboard/Control Method Chooser": "String Chooser",
"/SmartDashboard/Module 0": "Mechanism2d",
"/SmartDashboard/Module 1": "Mechanism2d",
"/SmartDashboard/Module 2": "Mechanism2d",
"/SmartDashboard/Module 3": "Mechanism2d",
"/SmartDashboard/Speed Chooser": "String Chooser"
}
},
"NetworkTables Info": {
"Clients": {
"open": true
},
"Connections": {
"open": true
},
"Server": {
"open": true
},
"visible": true
}
}
51 changes: 39 additions & 12 deletions src/main/java/frc/robot/RobotContainer.kt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@ import edu.wpi.first.math.geometry.Pose2d
import edu.wpi.first.math.geometry.Rotation2d
import edu.wpi.first.math.geometry.Translation2d
import edu.wpi.first.wpilibj.DriverStation
import edu.wpi.first.wpilibj.RobotBase
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard
import edu.wpi.first.wpilibj2.command.Command
import edu.wpi.first.wpilibj2.command.Commands
import edu.wpi.first.wpilibj2.command.button.CommandXboxController
Expand All @@ -30,9 +33,13 @@ import kotlin.math.cos
import kotlin.math.sin

class RobotContainer {
private val autoChooser: LoggedDashboardChooser<Command>
private val controlChooser: LoggedDashboardChooser<String> = LoggedDashboardChooser<String>("Control Method Chooser")
private val speedChooser: LoggedDashboardChooser<Double> = LoggedDashboardChooser<Double>("Speed Chooser")
private val autoChooser: LoggedDashboardChooser<Command> // auto chooser

private val controlChooser: SendableChooser<String> = SendableChooser()
private val controlChooserLogger: LoggedDashboardChooser<String>

private val speedChooser: SendableChooser<Double> = SendableChooser()
private val speedChooserLogger: LoggedDashboardChooser<Double>
private var MaxSpeed: Double = TunerConstants.kSpeedAt12VoltsMps // Initial max is true top speed
private val TurtleSpeed = 0.1 // Reduction in speed from Max Speed, 0.1 = 10%
private val MaxAngularRate =
Expand Down Expand Up @@ -76,6 +83,7 @@ class RobotContainer {
private var lastSpeed = 0.65

private fun configureBindings() {
SmartDashboard.putData("Auto Chooser", autoChooser.sendableChooser)
newControlStyle()
newSpeed()

Expand Down Expand Up @@ -106,7 +114,7 @@ class RobotContainer {
)
drv.leftBumper().onFalse(
Commands.runOnce({
MaxSpeed = TunerConstants.kSpeedAt12VoltsMps * speedChooser.get()
MaxSpeed = TunerConstants.kSpeedAt12VoltsMps * speedChooserLogger.get()
})
.andThen({ AngularRate = MaxAngularRate }),
)
Expand All @@ -116,10 +124,10 @@ class RobotContainer {
}
drivetrain.registerTelemetry { state: SwerveDrivetrain.SwerveDriveState -> logger.telemeterize(state) }

val controlPick = Trigger { lastControl !== controlChooser.get() }
val controlPick = Trigger { lastControl !== controlChooserLogger.get() }
controlPick.onTrue(Commands.runOnce({ newControlStyle() }))

val speedPick = Trigger { lastSpeed !== speedChooser.get() }
val speedPick = Trigger { lastSpeed !== try { speedChooserLogger.get()!! } catch (e: Throwable) {0.65} }
speedPick.onTrue(Commands.runOnce({ newSpeed() }))

drv.x().and(drv.pov(0)).whileTrue(drivetrain.runDriveQuasiTest(SysIdRoutine.Direction.kForward))
Expand Down Expand Up @@ -148,10 +156,11 @@ class RobotContainer {
// Build an auto chooser. This will use Commands.none() as the default option.
autoChooser = LoggedDashboardChooser("Auto Chooser", AutoBuilder.buildAutoChooser())

controlChooser.addDefaultOption("2 Joysticks", "2 Joysticks")
controlChooser.addOption("1 Joystick Rotation Triggers", "1 Joystick Rotation Triggers")
controlChooser.addOption("Split Joysticks Rotation Triggers", "Split Joysticks Rotation Triggers")
controlChooser.addOption("2 Joysticks with Gas Pedal", "2 Joysticks with Gas Pedal")
controlChooser.setDefaultOption("2 Joysticks", "2 Joysticks")
controlChooserLogger = LoggedDashboardChooser("Control Chooser", controlChooser)

speedChooser.addOption("100%", 1.0)
speedChooser.addOption("95%", 0.95)
Expand All @@ -160,11 +169,12 @@ class RobotContainer {
speedChooser.addOption("80%", 0.8)
speedChooser.addOption("75%", 0.75)
speedChooser.addOption("70%", 0.7)
speedChooser.addDefaultOption("65%", 0.65)
speedChooser.setDefaultOption("65%", 0.65)
speedChooser.addOption("60%", 0.6)
speedChooser.addOption("55%", 0.55)
speedChooser.addOption("50%", 0.5)
speedChooser.addOption("35%", 0.35)
speedChooserLogger = LoggedDashboardChooser("Speed Chooser", speedChooser)

configureBindings()
}
Expand All @@ -174,8 +184,8 @@ class RobotContainer {
autoChooser.get()

private fun newControlStyle() {
lastControl = controlChooser.get()
when (controlChooser.get()) {
lastControl = if(controlChooserLogger.get() != null) controlChooserLogger.get() else "2 Joysticks"
when (controlChooserLogger.get()) {
"2 Joysticks" -> controlStyle = Supplier<SwerveRequest?> {
drive.withVelocityX(-drv.leftY * MaxSpeed) // Drive forward -Y
.withVelocityY(-drv.leftX * MaxSpeed) // Drive left with negative X (left)
Expand All @@ -201,17 +211,34 @@ class RobotContainer {
.withVelocityY(sin(angle) * drv.rightTriggerAxis * MaxSpeed) // Angle of left stick Y * gas pedal
.withRotationalRate(-drv.rightX * AngularRate) // Drive counterclockwise with negative X (left)
}

else -> {
DriverStation.reportWarning("RC: Invalid control style: " + controlChooserLogger.get(), false)
controlStyle = Supplier<SwerveRequest?> {
drive.withVelocityX(-drv.leftY * MaxSpeed) // Drive forward -Y
.withVelocityY(-drv.leftX * MaxSpeed) // Drive left with negative X (left)
.withRotationalRate(-drv.rightX * AngularRate)
}
}
}
try {
drivetrain.defaultCommand.cancel()
} catch (_: Exception) {
DriverStation.reportWarning("RC: Failed to cancel default command", false)
DriverStation.reportWarning("RC: Failed to cancel default command? Maybe something else...", true)
controlStyle = Supplier<SwerveRequest?> {
drive.withVelocityX(-drv.leftY * MaxSpeed) // Drive forward -Y
.withVelocityY(-drv.leftX * MaxSpeed) // Drive left with negative X (left)
.withRotationalRate(-drv.rightX * AngularRate)
}
}
drivetrain.defaultCommand = drivetrain.applyRequest(controlStyle!!).ignoringDisable(true)
}

private fun newSpeed() {
lastSpeed = speedChooser.get()
try { lastSpeed = speedChooserLogger.get() } catch (_: Exception) {
DriverStation.reportWarning("RC: Failed to get speed, value is: " + speedChooserLogger.get(), false)
lastSpeed = 0.65
}
MaxSpeed = TunerConstants.kSpeedAt12VoltsMps * lastSpeed
}

Expand Down

0 comments on commit d16b0dc

Please sign in to comment.