From 37d677cf8aef021a03f48f8fe6e841d1f1305ce8 Mon Sep 17 00:00:00 2001 From: Hunter Barclay Date: Thu, 19 Dec 2024 16:46:20 -0700 Subject: [PATCH] [AARD-1864] Code Simulation: Configuration & Auto Testing (#1111) * feat: Add d3, test using it for path graphics * feat(sim): Nodes and edges rendering correctly * feat(task): Labels * Evaluable units in progress * fix(sim): Bug fixing and reworking unit evaluations and graph representation * feat(sim): Working on modules and layout * feat(sim): Modules rendering with rounded corners and proper portions * experiment: Tinkering with ReactFlow * feat(sim): Saving bespoke graph work * test: Sample custom node * feat!: Custom nodes laid out * feat!: Working on grabbing simulation data and indivudual config menus * Still need IDs for drivers and signals implemented * feat!: Working on edge validation * feat!: Slowly refactoring to include proper validation * feat!: Edge creation validation Currently isn't recreating edges correctly * Still debugging * Working through edge deletion * feat!: Node construction and deconstructions Node placement is off and deconstruction is untested. * feat!: Working on alternative functions and such * feat: SimUI compilation * Compilation untested * Compilation tested. Moving on to saving * Weird react hook issues * feat: Code sim configuration working with multiple robots * feat: Auto panel, new sample for testing auto routine * cleanup: Format and lint * cleanup: Format fixes * fix: Gampieces using wrong ID for mirabuf mapping * fix: Sorting and version numbers for mirabuf files * fix: Changed import delete button to say remove instead * cleanup: Format exporter and fission * cleanup: Remove console trace * cleanup: Comments and removals --- .../src/UI/GamepieceConfigTab.py | 3 +- fission/package.json | 1 + fission/src/Synthesis.tsx | 6 + fission/src/aps/APS.ts | 4 - .../src/mirabuf/IntakeSensorSceneObject.ts | 6 +- fission/src/mirabuf/MirabufSceneObject.ts | 117 ++- fission/src/systems/World.ts | 17 +- fission/src/systems/physics/PhysicsSystem.ts | 23 + .../systems/preferences/PreferenceTypes.ts | 4 + fission/src/systems/simulation/Brain.ts | 10 +- fission/src/systems/simulation/Nora.ts | 54 ++ .../systems/simulation/SimulationSystem.ts | 79 +- .../synthesis/GamepieceManipBehavior.ts | 26 + .../src/systems/simulation/driver/Driver.ts | 58 +- .../simulation/driver/EjectorDriver.ts | 33 + .../systems/simulation/driver/HingeDriver.ts | 19 +- .../systems/simulation/driver/IntakeDriver.ts | 33 + .../systems/simulation/driver/SliderDriver.ts | 17 +- .../systems/simulation/driver/WheelDriver.ts | 16 +- .../simulation/stimulus/ChassisStimulus.ts | 17 +- .../simulation/stimulus/EncoderStimulus.ts | 6 +- .../simulation/stimulus/HingeStimulus.ts | 16 +- .../simulation/stimulus/SliderStimulus.ts | 16 +- .../systems/simulation/stimulus/Stimulus.ts | 51 +- .../simulation/stimulus/WheelStimulus.ts | 16 +- .../synthesis_brain/SynthesisBrain.ts | 35 +- .../simulation/wpilib_brain/SimDataFlow.ts | 70 ++ .../simulation/wpilib_brain/WPILibBrain.ts | 254 +++++- .../simulation/wpilib_brain/WPILibWSWorker.ts | 51 +- fission/src/test/ui/SelectMenu.test.tsx | 2 +- fission/src/ui/components/BespokeGraph.tsx | 525 +++++++++++ fission/src/ui/components/Panel.tsx | 10 +- fission/src/ui/components/SelectMenu.tsx | 6 +- .../ui/components/WPILibConnectionStatus.tsx | 30 + .../rio-config/RCConfigCANGroupModal.tsx | 4 +- .../rio-config/RCConfigEncoderModal.tsx | 4 +- .../rio-config/RCConfigPWMGroupModal.tsx | 4 +- .../rio-config/RCCreateDeviceModal.tsx | 3 +- fission/src/ui/panels/DebugPanel.tsx | 20 - fission/src/ui/panels/WSViewPanel.tsx | 65 +- .../assembly-config/ConfigurePanel.tsx | 102 ++- .../assembly-config/ConfigurePanelControls.ts | 4 +- .../interfaces/BrainSelectionInterface.tsx | 45 + .../ConfigureSubsystemsInterface.tsx | 2 +- .../interfaces/SimulationInterface.tsx | 45 + .../inputs/ConfigureInputsInterface.tsx | 6 +- .../initial-config/InitialConfigPanel.tsx | 2 +- .../ui/panels/mirabuf/ImportMirabufPanel.tsx | 144 +-- .../ui/panels/simulation/AutoTestPanel.tsx | 364 ++++++++ .../src/ui/panels/simulation/FlowControls.tsx | 39 + fission/src/ui/panels/simulation/FlowInfo.tsx | 15 + .../ui/panels/simulation/SimConfigShared.ts | 835 ++++++++++++++++++ .../ui/panels/simulation/TextUpdaterNode.tsx | 30 + .../src/ui/panels/simulation/WiringNode.tsx | 126 +++ .../src/ui/panels/simulation/WiringPanel.tsx | 488 ++++++++++ fission/src/util/Units.ts | 73 ++ fission/src/util/Utility.ts | 5 + .../synthesis/revrobotics/CANSparkMax.java | 6 +- .../revrobotics/RelativeEncoder.java | 102 +++ simulation/samples/JavaAutoSample/.gitignore | 11 + .../samples/JavaAutoSample/WPILib-License.md | 24 + .../samples/JavaAutoSample/build.gradle | 115 +++ .../gradle/wrapper/gradle-wrapper.jar | Bin 0 -> 43462 bytes .../gradle/wrapper/gradle-wrapper.properties | 7 + simulation/samples/JavaAutoSample/gradlew | 249 ++++++ simulation/samples/JavaAutoSample/gradlew.bat | 92 ++ .../samples/JavaAutoSample/settings.gradle | 30 + .../src/main/deploy/example.txt | 3 + .../src/main/java/frc/robot/Main.java | 25 + .../src/main/java/frc/robot/Robot.java | 161 ++++ .../JavaAutoSample/vendordeps/NavX.json | 40 + .../JavaAutoSample/vendordeps/Phoenix6.json | 339 +++++++ .../JavaAutoSample/vendordeps/REVLib.json | 74 ++ .../src/main/java/frc/robot/Robot.java | 63 +- 74 files changed, 5087 insertions(+), 310 deletions(-) create mode 100644 fission/src/systems/simulation/Nora.ts create mode 100644 fission/src/systems/simulation/behavior/synthesis/GamepieceManipBehavior.ts create mode 100644 fission/src/systems/simulation/driver/EjectorDriver.ts create mode 100644 fission/src/systems/simulation/driver/IntakeDriver.ts create mode 100644 fission/src/systems/simulation/wpilib_brain/SimDataFlow.ts create mode 100644 fission/src/ui/components/BespokeGraph.tsx create mode 100644 fission/src/ui/components/WPILibConnectionStatus.tsx create mode 100644 fission/src/ui/panels/configuring/assembly-config/interfaces/BrainSelectionInterface.tsx create mode 100644 fission/src/ui/panels/configuring/assembly-config/interfaces/SimulationInterface.tsx create mode 100644 fission/src/ui/panels/simulation/AutoTestPanel.tsx create mode 100644 fission/src/ui/panels/simulation/FlowControls.tsx create mode 100644 fission/src/ui/panels/simulation/FlowInfo.tsx create mode 100644 fission/src/ui/panels/simulation/SimConfigShared.ts create mode 100644 fission/src/ui/panels/simulation/TextUpdaterNode.tsx create mode 100644 fission/src/ui/panels/simulation/WiringNode.tsx create mode 100644 fission/src/ui/panels/simulation/WiringPanel.tsx create mode 100644 fission/src/util/Units.ts create mode 100644 simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/RelativeEncoder.java create mode 100644 simulation/samples/JavaAutoSample/.gitignore create mode 100644 simulation/samples/JavaAutoSample/WPILib-License.md create mode 100644 simulation/samples/JavaAutoSample/build.gradle create mode 100644 simulation/samples/JavaAutoSample/gradle/wrapper/gradle-wrapper.jar create mode 100644 simulation/samples/JavaAutoSample/gradle/wrapper/gradle-wrapper.properties create mode 100644 simulation/samples/JavaAutoSample/gradlew create mode 100644 simulation/samples/JavaAutoSample/gradlew.bat create mode 100644 simulation/samples/JavaAutoSample/settings.gradle create mode 100644 simulation/samples/JavaAutoSample/src/main/deploy/example.txt create mode 100644 simulation/samples/JavaAutoSample/src/main/java/frc/robot/Main.java create mode 100644 simulation/samples/JavaAutoSample/src/main/java/frc/robot/Robot.java create mode 100644 simulation/samples/JavaAutoSample/vendordeps/NavX.json create mode 100644 simulation/samples/JavaAutoSample/vendordeps/Phoenix6.json create mode 100644 simulation/samples/JavaAutoSample/vendordeps/REVLib.json diff --git a/exporter/SynthesisFusionAddin/src/UI/GamepieceConfigTab.py b/exporter/SynthesisFusionAddin/src/UI/GamepieceConfigTab.py index c28f6c60f1..842389a667 100644 --- a/exporter/SynthesisFusionAddin/src/UI/GamepieceConfigTab.py +++ b/exporter/SynthesisFusionAddin/src/UI/GamepieceConfigTab.py @@ -3,6 +3,7 @@ from src.Logging import logFailure from src.Parser.ExporterOptions import ExporterOptions +from src.Parser.SynthesisParser.Utilities import guid_occurrence from src.Types import Gamepiece, UnitSystem from src.UI.CreateCommandInputsHelper import ( createBooleanInput, @@ -198,7 +199,7 @@ def removeChildOccurrences(childOccurrences: adsk.fusion.OccurrenceList) -> None def getGamepieces(self) -> list[Gamepiece]: gamepieces: list[Gamepiece] = [] for row in range(1, self.gamepieceTable.rowCount): # Row is 1 indexed - gamepieceEntityToken = self.selectedGamepieceList[row - 1].entityToken + gamepieceEntityToken = guid_occurrence(self.selectedGamepieceList[row - 1]) gamepieceWeight = convertMassUnitsTo(self.gamepieceTable.getInputAtPosition(row, 1).value) gamepieceFrictionCoefficient = self.gamepieceTable.getInputAtPosition(row, 2).valueOne gamepieces.append(Gamepiece(gamepieceEntityToken, gamepieceWeight, gamepieceFrictionCoefficient)) diff --git a/fission/package.json b/fission/package.json index b35a21e462..41c7e0f76c 100644 --- a/fission/package.json +++ b/fission/package.json @@ -30,6 +30,7 @@ "@react-three/fiber": "^8.15.15", "@vitest/browser": "^1.6.0", "@vitest/coverage-v8": "^1.6.0", + "@xyflow/react": "^12.3.2", "async-mutex": "^0.5.0", "colord": "^2.9.3", "framer-motion": "^10.13.1", diff --git a/fission/src/Synthesis.tsx b/fission/src/Synthesis.tsx index ec18ba6bc8..8738695b69 100644 --- a/fission/src/Synthesis.tsx +++ b/fission/src/Synthesis.tsx @@ -58,10 +58,13 @@ import AnalyticsConsent from "./ui/components/AnalyticsConsent.tsx" import PreferencesSystem from "./systems/preferences/PreferencesSystem.ts" import APSManagementModal from "./ui/modals/APSManagementModal.tsx" import ConfigurePanel from "./ui/panels/configuring/assembly-config/ConfigurePanel.tsx" +import WiringPanel from "./ui/panels/simulation/WiringPanel.tsx" import CameraSelectionPanel from "./ui/panels/configuring/CameraSelectionPanel.tsx" import ContextMenu from "./ui/components/ContextMenu.tsx" import GlobalUIComponent from "./ui/components/GlobalUIComponent.tsx" import InitialConfigPanel from "./ui/panels/configuring/initial-config/InitialConfigPanel.tsx" +import WPILibConnectionStatus from "./ui/components/WPILibConnectionStatus.tsx" +import AutoTestPanel from "./ui/panels/simulation/AutoTestPanel.tsx" function Synthesis() { const { openModal, closeModal, getActiveModalElement } = useModalManager(initialModals) @@ -173,6 +176,7 @@ function Synthesis() { )} + {!consentPopupDisable ? ( @@ -228,8 +232,10 @@ const initialPanels: ReactElement[] = [ , , , + , , , + , ] export default Synthesis diff --git a/fission/src/aps/APS.ts b/fission/src/aps/APS.ts index d9ae0500e3..ff6f1204ad 100644 --- a/fission/src/aps/APS.ts +++ b/fission/src/aps/APS.ts @@ -339,10 +339,6 @@ class APS { email: json.email, } - if (json.sub) { - World.AnalyticsSystem?.SetUserId(json.sub as string) - } - this.userInfo = info } catch (e) { console.error(e) diff --git a/fission/src/mirabuf/IntakeSensorSceneObject.ts b/fission/src/mirabuf/IntakeSensorSceneObject.ts index bd8986afbe..de33d2dc6d 100644 --- a/fission/src/mirabuf/IntakeSensorSceneObject.ts +++ b/fission/src/mirabuf/IntakeSensorSceneObject.ts @@ -11,8 +11,6 @@ import { ThreeVector3_JoltVec3, } from "@/util/TypeConversions" import { OnContactPersistedEvent } from "@/systems/physics/ContactEvents" -import InputSystem from "@/systems/input/InputSystem" -import SynthesisBrain from "@/systems/simulation/synthesis_brain/SynthesisBrain" class IntakeSensorSceneObject extends SceneObject { private _parentAssembly: MirabufSceneObject @@ -44,9 +42,7 @@ class IntakeSensorSceneObject extends SceneObject { } this._collision = (event: OnContactPersistedEvent) => { - const brain = this._parentAssembly.brain - const brainIndex = brain instanceof SynthesisBrain ? brain.brainIndex ?? -1 : -1 - if (InputSystem.getInput("intake", brainIndex)) { + if (this._parentAssembly.intakeActive) { if (this._joltBodyId && !World.PhysicsSystem.isPaused) { const body1 = event.message.body1 const body2 = event.message.body2 diff --git a/fission/src/mirabuf/MirabufSceneObject.ts b/fission/src/mirabuf/MirabufSceneObject.ts index 886f7ca137..3a78803a1c 100644 --- a/fission/src/mirabuf/MirabufSceneObject.ts +++ b/fission/src/mirabuf/MirabufSceneObject.ts @@ -9,7 +9,6 @@ import * as THREE from "three" import JOLT from "@/util/loading/JoltSyncLoader" import { BodyAssociate, LayerReserve } from "@/systems/physics/PhysicsSystem" import Mechanism from "@/systems/physics/Mechanism" -import InputSystem from "@/systems/input/InputSystem" import { EjectorPreferences, FieldPreferences, IntakePreferences } from "@/systems/preferences/PreferenceTypes" import PreferencesSystem from "@/systems/preferences/PreferencesSystem" import { MiraType } from "./MirabufLoader" @@ -32,6 +31,8 @@ import { ConfigurationType, setSelectedConfigurationType, } from "@/ui/panels/configuring/assembly-config/ConfigurationType" +import { SimConfigData } from "@/ui/panels/simulation/SimConfigShared" +import WPILibBrain from "@/systems/simulation/wpilib_brain/WPILibBrain" const DEBUG_BODIES = false @@ -68,6 +69,7 @@ class MirabufSceneObject extends SceneObject implements ContextSupplier { private _intakePreferences: IntakePreferences | undefined private _ejectorPreferences: EjectorPreferences | undefined + private _simConfigData: SimConfigData | undefined private _fieldPreferences: FieldPreferences | undefined @@ -77,6 +79,22 @@ class MirabufSceneObject extends SceneObject implements ContextSupplier { private _nameTag: SceneOverlayTag | undefined + private _intakeActive = false + private _ejectorActive = false + + public get intakeActive() { + return this._intakeActive + } + public get ejectorActive() { + return this._ejectorActive + } + public set intakeActive(a: boolean) { + this._intakeActive = a + } + public set ejectorActive(a: boolean) { + this._ejectorActive = a + } + get mirabufInstance() { return this._mirabufInstance } @@ -97,6 +115,10 @@ class MirabufSceneObject extends SceneObject implements ContextSupplier { return this._ejectorPreferences } + get simConfigData() { + return this._simConfigData + } + get fieldPreferences() { return this._fieldPreferences } @@ -117,6 +139,12 @@ class MirabufSceneObject extends SceneObject implements ContextSupplier { return this._brain } + public set brain(brain: Brain | undefined) { + this._brain = brain + const simLayer = World.SimulationSystem.GetSimulationLayer(this._mechanism)! + simLayer.SetBrain(brain) + } + public constructor(mirabufInstance: MirabufInstance, assemblyName: string, progressHandle?: ProgressHandle) { super() @@ -137,7 +165,11 @@ class MirabufSceneObject extends SceneObject implements ContextSupplier { // creating nametag for robots if (this.miraType === MiraType.ROBOT) { this._nameTag = new SceneOverlayTag(() => - this._brain instanceof SynthesisBrain ? this._brain.inputSchemeName : "Not Configured" + this._brain instanceof SynthesisBrain + ? this._brain.inputSchemeName + : this._brain instanceof WPILibBrain + ? "Magic" + : "Not Configured" ) } } @@ -177,7 +209,7 @@ class MirabufSceneObject extends SceneObject implements ContextSupplier { if (this.miraType == MiraType.ROBOT) { World.SimulationSystem.RegisterMechanism(this._mechanism) const simLayer = World.SimulationSystem.GetSimulationLayer(this._mechanism)! - this._brain = new SynthesisBrain(this._mechanism, this._assemblyName) + this._brain = new SynthesisBrain(this, this._assemblyName) simLayer.SetBrain(this._brain) } @@ -212,13 +244,11 @@ class MirabufSceneObject extends SceneObject implements ContextSupplier { } public Update(): void { - const brainIndex = this._brain instanceof SynthesisBrain ? this._brain.brainIndex ?? -1 : -1 - if (InputSystem.getInput("eject", brainIndex)) { + if (this.ejectorActive) { this.Eject() } this.UpdateMeshTransforms() - this.UpdateBatches() this.UpdateNameTag() } @@ -456,12 +486,26 @@ class MirabufSceneObject extends SceneObject implements ContextSupplier { } private getPreferences(): void { - this._intakePreferences = PreferencesSystem.getRobotPreferences(this.assemblyName)?.intake - this._ejectorPreferences = PreferencesSystem.getRobotPreferences(this.assemblyName)?.ejector + const robotPrefs = PreferencesSystem.getRobotPreferences(this.assemblyName) + if (robotPrefs) { + this._intakePreferences = robotPrefs.intake + this._ejectorPreferences = robotPrefs.ejector + this._simConfigData = robotPrefs.simConfig + } this._fieldPreferences = PreferencesSystem.getFieldPreferences(this.assemblyName) } + public UpdateSimConfig(config: SimConfigData | undefined) { + const robotPrefs = PreferencesSystem.getRobotPreferences(this.assemblyName) + if (robotPrefs) { + this._simConfigData = robotPrefs.simConfig = config + PreferencesSystem.setRobotPreferences(this.assemblyName, robotPrefs) + PreferencesSystem.savePreferences() + ;(this._brain as WPILibBrain)?.loadSimConfig?.() + } + } + public EnablePhysics() { this._mirabufInstance.parser.rigidNodes.forEach(rn => { World.PhysicsSystem.EnablePhysicsForBody(this._mechanism.GetBodyByNodeId(rn.id)!) @@ -488,31 +532,42 @@ class MirabufSceneObject extends SceneObject implements ContextSupplier { public getSupplierData(): ContextData { const data: ContextData = { title: this.miraType == MiraType.ROBOT ? "A Robot" : "A Field", items: [] } - data.items.push({ - name: "Move", - func: () => { - setSelectedConfigurationType( - this.miraType == MiraType.ROBOT ? ConfigurationType.ROBOT : ConfigurationType.FIELD - ) - setNextConfigurePanelSettings({ - configMode: ConfigMode.MOVE, - selectedAssembly: this, - }) - Global_OpenPanel?.("configure") + data.items.push( + { + name: "Move", + func: () => { + setSelectedConfigurationType( + this.miraType == MiraType.ROBOT ? ConfigurationType.ROBOT : ConfigurationType.FIELD + ) + setNextConfigurePanelSettings({ + configMode: ConfigMode.MOVE, + selectedAssembly: this, + }) + Global_OpenPanel?.("configure") + }, }, - }) - - if (this.miraType == MiraType.ROBOT) { - const brainIndex = (this.brain as SynthesisBrain)?.brainIndex - if (brainIndex != undefined) { - data.items.push({ - name: "Set Scheme", - func: () => { - setSpotlightAssembly(this) - Global_OpenPanel?.("choose-scheme") - }, - }) + { + name: "Configure", + func: () => { + setSelectedConfigurationType( + this.miraType == MiraType.ROBOT ? ConfigurationType.ROBOT : ConfigurationType.FIELD + ) + setNextConfigurePanelSettings({ + configMode: undefined, + selectedAssembly: this, + }) + Global_OpenPanel?.("configure") + }, } + ) + + if (this.brain?.brainType == "wpilib") { + data.items.push({ + name: "Auto Testing", + func: () => { + Global_OpenPanel?.("auto-test") + }, + }) } if (World.SceneRenderer.currentCameraControls.controlsType == "Orbit") { diff --git a/fission/src/systems/World.ts b/fission/src/systems/World.ts index 6a7ee44e4a..a1389e80cd 100644 --- a/fission/src/systems/World.ts +++ b/fission/src/systems/World.ts @@ -9,6 +9,7 @@ import AnalyticsSystem, { AccumTimes } from "./analytics/AnalyticsSystem" class World { private static _isAlive: boolean = false private static _clock: THREE.Clock + private static _currentDeltaT: number = 0 private static _sceneRenderer: SceneRenderer private static _physicsSystem: PhysicsSystem @@ -91,18 +92,22 @@ class World { } public static UpdateWorld() { - const deltaT = World._clock.getDelta() + this._currentDeltaT = World._clock.getDelta() this._accumTimes.frames++ this._accumTimes.totalTime += this.time(() => { - this._accumTimes.simulationTime += this.time(() => World._simulationSystem.Update(deltaT)) - this._accumTimes.physicsTime += this.time(() => World._physicsSystem.Update(deltaT)) - this._accumTimes.inputTime += this.time(() => World._inputSystem.Update(deltaT)) - this._accumTimes.sceneTime += this.time(() => World._sceneRenderer.Update(deltaT)) + this._accumTimes.simulationTime += this.time(() => World._simulationSystem.Update(this._currentDeltaT)) + this._accumTimes.physicsTime += this.time(() => World._physicsSystem.Update(this._currentDeltaT)) + this._accumTimes.inputTime += this.time(() => World._inputSystem.Update(this._currentDeltaT)) + this._accumTimes.sceneTime += this.time(() => World._sceneRenderer.Update(this._currentDeltaT)) }) - World._analyticsSystem?.Update(deltaT) + World._analyticsSystem?.Update(this._currentDeltaT) + } + + public static get currentDeltaT(): number { + return this._currentDeltaT } private static time(func: () => void): number { diff --git a/fission/src/systems/physics/PhysicsSystem.ts b/fission/src/systems/physics/PhysicsSystem.ts index 5635ac6721..9408d5c42a 100644 --- a/fission/src/systems/physics/PhysicsSystem.ts +++ b/fission/src/systems/physics/PhysicsSystem.ts @@ -1098,6 +1098,29 @@ class PhysicsSystem extends WorldSystem { ) } + public SetBodyPositionRotationAndVelocity( + id: Jolt.BodyID, + position: Jolt.RVec3, + rotation: Jolt.Quat, + linear: Jolt.Vec3, + angular: Jolt.Vec3, + activate: boolean = true + ): void { + if (!this.IsBodyAdded(id)) { + return + } + + this._joltBodyInterface.SetPositionAndRotation( + id, + position, + rotation, + activate ? JOLT.EActivation_Activate : JOLT.EActivation_DontActivate + ) + + this._joltBodyInterface.SetLinearVelocity(id, linear) + this._joltBodyInterface.SetAngularVelocity(id, angular) + } + /** * Exposes SetShape method on the _joltBodyInterface * Sets the shape of the body diff --git a/fission/src/systems/preferences/PreferenceTypes.ts b/fission/src/systems/preferences/PreferenceTypes.ts index 8c99e60d19..a1ea8ac352 100644 --- a/fission/src/systems/preferences/PreferenceTypes.ts +++ b/fission/src/systems/preferences/PreferenceTypes.ts @@ -1,3 +1,4 @@ +import { SimConfigData } from "@/ui/panels/simulation/SimConfigShared" import { InputScheme } from "../input/InputSchemeManager" import { Vector3Tuple } from "three" @@ -14,6 +15,7 @@ export type GlobalPreference = | "RenderSceneTags" | "RenderScoreboard" | "SubsystemGravity" + | "SimAutoReconnect" export const RobotPreferencesKey: string = "Robots" export const FieldPreferencesKey: string = "Fields" @@ -34,6 +36,7 @@ export const DefaultGlobalPreferences: { [key: string]: unknown } = { RenderSceneTags: true, RenderScoreboard: true, SubsystemGravity: false, + SimAutoReconnect: false, } export type QualitySetting = "Low" | "Medium" | "High" @@ -79,6 +82,7 @@ export type RobotPreferences = { driveVelocity: number driveAcceleration: number sequentialConfig?: SequentialBehaviorPreferences[] + simConfig?: SimConfigData } export type MotorPreferences = { diff --git a/fission/src/systems/simulation/Brain.ts b/fission/src/systems/simulation/Brain.ts index d784195e8e..f8923574aa 100644 --- a/fission/src/systems/simulation/Brain.ts +++ b/fission/src/systems/simulation/Brain.ts @@ -1,10 +1,18 @@ import Mechanism from "../physics/Mechanism" +export type BrainType = "synthesis" | "wpilib" | "unknown" + abstract class Brain { protected _mechanism: Mechanism - constructor(mechanism: Mechanism) { + private _brainType: BrainType + public get brainType() { + return this._brainType + } + + constructor(mechanism: Mechanism, brainType: BrainType) { this._mechanism = mechanism + this._brainType = brainType } public abstract Update(deltaT: number): void diff --git a/fission/src/systems/simulation/Nora.ts b/fission/src/systems/simulation/Nora.ts new file mode 100644 index 0000000000..08f22832ef --- /dev/null +++ b/fission/src/systems/simulation/Nora.ts @@ -0,0 +1,54 @@ +/** + * To build input validation into the node editor, I had to + * make this poor man's type system. Please make it better. + * + * We should be able to assign identifiers to the types and + * probably have more in-tune mechanisms for handling the + * junction situations. Right now its kinda patched together + * with the averaging function setup I have below. + */ + +export enum NoraTypes { + Number = "num", + Number2 = "(num,num)", + Number3 = "(num,num,num)", + Unknown = "unknown", +} + +export type NoraNumber = number +export type NoraNumber2 = [NoraNumber, NoraNumber] +export type NoraNumber3 = [NoraNumber, NoraNumber, NoraNumber] +export type NoraUnknown = unknown + +export type NoraType = NoraNumber | NoraNumber2 | NoraNumber3 | NoraUnknown + +// Needed? +// export function constructNoraType(...types: NoraTypes[]): NoraTypes { +// return `[${types.join(",")}]` as NoraTypes +// } + +export function deconstructNoraType(type: NoraTypes): NoraTypes[] | undefined { + if (type.charAt(0) != "(" || type.charAt(type.length - 1) != ")") return undefined + return type.substring(1, type.length - 1).split(",") as NoraTypes[] +} + +export function isNoraDeconstructable(type: NoraTypes): boolean { + return type.charAt(0) == "(" && type.charAt(type.length - 1) == ")" +} + +const averageFuncMap: { [k in NoraTypes]: ((...many: NoraType[]) => NoraType) | undefined } = { + [NoraTypes.Number]: function (...many: NoraType[]): NoraType { + return many.reduce((prev, next) => (prev += next as NoraNumber), 0) + }, + [NoraTypes.Number2]: undefined, + [NoraTypes.Number3]: undefined, + [NoraTypes.Unknown]: undefined, +} + +export function noraAverageFunc(type: NoraTypes): ((...many: NoraType[]) => NoraType) | undefined { + return averageFuncMap[type] +} + +export function hasNoraAverageFunc(type: NoraTypes): boolean { + return averageFuncMap[type] != undefined +} diff --git a/fission/src/systems/simulation/SimulationSystem.ts b/fission/src/systems/simulation/SimulationSystem.ts index d3d05370d4..bfaa2c39de 100644 --- a/fission/src/systems/simulation/SimulationSystem.ts +++ b/fission/src/systems/simulation/SimulationSystem.ts @@ -2,8 +2,8 @@ import JOLT from "@/util/loading/JoltSyncLoader" import Mechanism from "../physics/Mechanism" import WorldSystem from "../WorldSystem" import Brain from "./Brain" -import Driver from "./driver/Driver" -import Stimulus from "./stimulus/Stimulus" +import Driver, { DriverType, makeDriverID } from "./driver/Driver" +import Stimulus, { makeStimulusID, StimulusType } from "./stimulus/Stimulus" import HingeDriver from "./driver/HingeDriver" import WheelDriver from "./driver/WheelDriver" import SliderDriver from "./driver/SliderDriver" @@ -11,6 +11,10 @@ import HingeStimulus from "./stimulus/HingeStimulus" import WheelRotationStimulus from "./stimulus/WheelStimulus" import SliderStimulus from "./stimulus/SliderStimulus" import ChassisStimulus from "./stimulus/ChassisStimulus" +import IntakeDriver from "./driver/IntakeDriver" +import World from "../World" +import MirabufSceneObject from "@/mirabuf/MirabufSceneObject" +import EjectorDriver from "./driver/EjectorDriver" class SimulationSystem extends WorldSystem { private _simMechanisms: Map @@ -63,47 +67,72 @@ class SimulationLayer { private _mechanism: Mechanism private _brain?: Brain - private _drivers: Driver[] - private _stimuli: Stimulus[] + private _drivers: Map + private _stimuli: Map public get brain() { return this._brain } public get drivers() { - return this._drivers + return [...this._drivers.values()] } public get stimuli() { - return this._stimuli + return [...this._stimuli.values()] } constructor(mechanism: Mechanism) { this._mechanism = mechanism + const assembly = [...World.SceneRenderer.sceneObjects.values()].find( + x => (x as MirabufSceneObject).mechanism == mechanism + ) as MirabufSceneObject + // Generate standard drivers and stimuli - this._drivers = [] - this._stimuli = [] + this._drivers = new Map() + this._stimuli = new Map() this._mechanism.constraints.forEach(x => { if (x.constraint.GetSubType() == JOLT.EConstraintSubType_Hinge) { const hinge = JOLT.castObject(x.constraint, JOLT.HingeConstraint) - const driver = new HingeDriver(hinge, x.maxVelocity, x.info) - this._drivers.push(driver) - const stim = new HingeStimulus(hinge, x.info) - this._stimuli.push(stim) + const driver = new HingeDriver(makeDriverID(x), hinge, x.maxVelocity, x.info) + this._drivers.set(JSON.stringify(driver.id), driver) + const stim = new HingeStimulus(makeStimulusID(x), hinge, x.info) + this._stimuli.set(JSON.stringify(stim.id), stim) } else if (x.constraint.GetSubType() == JOLT.EConstraintSubType_Vehicle) { const vehicle = JOLT.castObject(x.constraint, JOLT.VehicleConstraint) - const driver = new WheelDriver(vehicle, x.maxVelocity, x.info) - this._drivers.push(driver) - const stim = new WheelRotationStimulus(vehicle.GetWheel(0), x.info) - this._stimuli.push(stim) + const driver = new WheelDriver(makeDriverID(x), vehicle, x.maxVelocity, x.info) + this._drivers.set(JSON.stringify(driver.id), driver) + const stim = new WheelRotationStimulus(makeStimulusID(x), vehicle.GetWheel(0), x.info) + this._stimuli.set(JSON.stringify(stim.id), stim) } else if (x.constraint.GetSubType() == JOLT.EConstraintSubType_Slider) { const slider = JOLT.castObject(x.constraint, JOLT.SliderConstraint) - const driver = new SliderDriver(slider, x.maxVelocity, x.info) - this._drivers.push(driver) - const stim = new SliderStimulus(slider, x.info) - this._stimuli.push(stim) + const driver = new SliderDriver(makeDriverID(x), slider, x.maxVelocity, x.info) + this._drivers.set(JSON.stringify(driver.id), driver) + const stim = new SliderStimulus(makeStimulusID(x), slider, x.info) + this._stimuli.set(JSON.stringify(stim.id), stim) } }) - this._stimuli.push(new ChassisStimulus(mechanism.nodeToBody.get(mechanism.rootBody)!)) + + const chassisStim = new ChassisStimulus( + { type: StimulusType.Stim_ChassisAccel, guid: "CHASSIS_GUID" }, + mechanism.nodeToBody.get(mechanism.rootBody)!, + { GUID: "CHASSIS_GUID", name: "Chassis" } + ) + this._stimuli.set(JSON.stringify(chassisStim.id), chassisStim) + + if (assembly) { + const intakeDriv = new IntakeDriver({ type: DriverType.Driv_Intake, guid: "INTAKE_GUID" }, assembly, { + GUID: "INTAKE_GUID", + name: "Intake", + }) + const ejectorDriv = new EjectorDriver({ type: DriverType.Driv_Ejector, guid: "EJECTOR_GUID" }, assembly, { + GUID: "EJECTOR_GUID", + name: "Ejector", + }) + this._drivers.set(JSON.stringify(ejectorDriv.id), ejectorDriv) + this._drivers.set(JSON.stringify(intakeDriv.id), intakeDriv) + } else { + console.debug("No Assembly found with given mechanism, skipping intake and ejector...") + } } public Update(deltaT: number) { @@ -119,6 +148,14 @@ class SimulationLayer { if (this._brain) this._brain.Enable() } + + public GetStimuli(id: string) { + return this._stimuli.get(id) + } + + public GetDriver(id: string) { + return this._drivers.get(id) + } } export default SimulationSystem diff --git a/fission/src/systems/simulation/behavior/synthesis/GamepieceManipBehavior.ts b/fission/src/systems/simulation/behavior/synthesis/GamepieceManipBehavior.ts new file mode 100644 index 0000000000..bacee33a53 --- /dev/null +++ b/fission/src/systems/simulation/behavior/synthesis/GamepieceManipBehavior.ts @@ -0,0 +1,26 @@ +import Behavior from "@/systems/simulation/behavior/Behavior" +import InputSystem from "@/systems/input/InputSystem" +import EjectorDriver from "../../driver/EjectorDriver" +import IntakeDriver from "../../driver/IntakeDriver" + +class GamepieceManipBehavior extends Behavior { + private _brainIndex: number + + private _ejector: EjectorDriver + private _intake: IntakeDriver + + constructor(ejector: EjectorDriver, intake: IntakeDriver, brainIndex: number) { + super([ejector, intake], []) + + this._brainIndex = brainIndex + this._ejector = ejector + this._intake = intake + } + + public Update(_: number): void { + this._ejector.value = InputSystem.getInput("eject", this._brainIndex) + this._intake.value = InputSystem.getInput("intake", this._brainIndex) + } +} + +export default GamepieceManipBehavior diff --git a/fission/src/systems/simulation/driver/Driver.ts b/fission/src/systems/simulation/driver/Driver.ts index a6fbdb39f3..89679c685c 100644 --- a/fission/src/systems/simulation/driver/Driver.ts +++ b/fission/src/systems/simulation/driver/Driver.ts @@ -1,17 +1,71 @@ import { mirabuf } from "@/proto/mirabuf" +import { MechanismConstraint } from "@/systems/physics/Mechanism" +import JOLT from "@/util/loading/JoltSyncLoader" +import { NoraType, NoraTypes } from "../Nora" +import { SimReceiver } from "../wpilib_brain/SimDataFlow" -abstract class Driver { +export enum DriverType { + Driv_Hinge = "Driv_Hinge", + Driv_Wheel = "Driv_Wheel", + Driv_Slider = "Driv_Slider", + Driv_Intake = "Driv_Intake", + Driv_Ejector = "Driv_Ejector", + Driv_Unknown = "Driv_Unknown", +} + +export type DriverID = { + type: DriverType + name?: string + guid: string +} + +export function makeDriverID(constraint: MechanismConstraint): DriverID { + let driverType: DriverType = DriverType.Driv_Unknown + switch (constraint.constraint.GetSubType()) { + case JOLT.EConstraintSubType_Hinge: + driverType = DriverType.Driv_Hinge + break + case JOLT.EConstraintSubType_Slider: + driverType = DriverType.Driv_Slider + break + case JOLT.EConstraintSubType_Vehicle: + driverType = DriverType.Driv_Wheel + break + } + + return { + type: driverType, + name: constraint.info?.name ?? undefined, + guid: constraint.info?.GUID ?? "unknown", + } +} + +abstract class Driver implements SimReceiver { + private _id: DriverID private _info?: mirabuf.IInfo - constructor(info?: mirabuf.IInfo) { + constructor(id: DriverID, info?: mirabuf.IInfo) { + this._id = id this._info = info } public abstract Update(deltaT: number): void + public get id() { + return this._id + } + + public get idStr() { + return JSON.stringify(this._id) + } + public get info() { return this._info } + + public abstract setReceiverValue(val: NoraType): void + public abstract getReceiverType(): NoraTypes + public abstract DisplayName(): string } export enum DriverControlMode { diff --git a/fission/src/systems/simulation/driver/EjectorDriver.ts b/fission/src/systems/simulation/driver/EjectorDriver.ts new file mode 100644 index 0000000000..b23fe12d2a --- /dev/null +++ b/fission/src/systems/simulation/driver/EjectorDriver.ts @@ -0,0 +1,33 @@ +import { mirabuf } from "@/proto/mirabuf" +import { NoraNumber, NoraTypes } from "../Nora" +import Driver, { DriverID } from "./Driver" +import MirabufSceneObject from "@/mirabuf/MirabufSceneObject" + +class EjectorDriver extends Driver { + public value: number + + private _assembly: MirabufSceneObject + + public constructor(id: DriverID, assembly: MirabufSceneObject, info?: mirabuf.IInfo) { + super(id, info) + + this._assembly = assembly + this.value = 0.0 + } + + public Update(_deltaT: number): void { + this._assembly.ejectorActive = this.value > 0.5 + } + + public setReceiverValue(val: NoraNumber): void { + this.value = val + } + public getReceiverType(): NoraTypes { + return NoraTypes.Number + } + public DisplayName(): string { + return "Ejector" + } +} + +export default EjectorDriver diff --git a/fission/src/systems/simulation/driver/HingeDriver.ts b/fission/src/systems/simulation/driver/HingeDriver.ts index 755994921d..cf860a4acf 100644 --- a/fission/src/systems/simulation/driver/HingeDriver.ts +++ b/fission/src/systems/simulation/driver/HingeDriver.ts @@ -1,9 +1,10 @@ import Jolt from "@barclah/jolt-physics" -import Driver, { DriverControlMode } from "./Driver" +import Driver, { DriverControlMode, DriverID } from "./Driver" import { GetLastDeltaT } from "@/systems/physics/PhysicsSystem" import JOLT from "@/util/loading/JoltSyncLoader" import { mirabuf } from "@/proto/mirabuf" import PreferencesSystem, { PreferenceEvent } from "@/systems/preferences/PreferencesSystem" +import { NoraNumber, NoraTypes } from "../Nora" const MAX_TORQUE_WITHOUT_GRAV = 100 @@ -60,8 +61,8 @@ class HingeDriver extends Driver { } } - public constructor(constraint: Jolt.HingeConstraint, maxVelocity: number, info?: mirabuf.IInfo) { - super(info) + public constructor(id: DriverID, constraint: Jolt.HingeConstraint, maxVelocity: number, info?: mirabuf.IInfo) { + super(id, info) this._constraint = constraint this.maxVelocity = maxVelocity @@ -110,6 +111,18 @@ class HingeDriver extends Driver { this._constraint.SetTargetAngle(ang) } } + + public getReceiverType(): NoraTypes { + return NoraTypes.Number + } + + public setReceiverValue(val: NoraNumber): void { + this.accelerationDirection = val + } + + public DisplayName(): string { + return `${this.info?.name ?? "-"} [Hinge]` + } } export default HingeDriver diff --git a/fission/src/systems/simulation/driver/IntakeDriver.ts b/fission/src/systems/simulation/driver/IntakeDriver.ts new file mode 100644 index 0000000000..e8ead3b52d --- /dev/null +++ b/fission/src/systems/simulation/driver/IntakeDriver.ts @@ -0,0 +1,33 @@ +import { mirabuf } from "@/proto/mirabuf" +import { NoraNumber, NoraTypes } from "../Nora" +import Driver, { DriverID } from "./Driver" +import MirabufSceneObject from "@/mirabuf/MirabufSceneObject" + +class IntakeDriver extends Driver { + public value: number + + private _assembly: MirabufSceneObject + + public constructor(id: DriverID, assembly: MirabufSceneObject, info?: mirabuf.IInfo) { + super(id, info) + + this._assembly = assembly + this.value = 0.0 + } + + public Update(_deltaT: number): void { + this._assembly.intakeActive = this.value > 0.5 + } + + public setReceiverValue(val: NoraNumber): void { + this.value = val + } + public getReceiverType(): NoraTypes { + return NoraTypes.Number + } + public DisplayName(): string { + return "Intake" + } +} + +export default IntakeDriver diff --git a/fission/src/systems/simulation/driver/SliderDriver.ts b/fission/src/systems/simulation/driver/SliderDriver.ts index eb80a871e6..e19d2aa3f2 100644 --- a/fission/src/systems/simulation/driver/SliderDriver.ts +++ b/fission/src/systems/simulation/driver/SliderDriver.ts @@ -1,9 +1,10 @@ import Jolt from "@barclah/jolt-physics" -import Driver, { DriverControlMode } from "./Driver" +import Driver, { DriverControlMode, DriverID } from "./Driver" import { GetLastDeltaT } from "@/systems/physics/PhysicsSystem" import JOLT from "@/util/loading/JoltSyncLoader" import { mirabuf } from "@/proto/mirabuf" import PreferencesSystem, { PreferenceEvent } from "@/systems/preferences/PreferencesSystem" +import { NoraNumber, NoraTypes } from "../Nora" const MAX_FORCE_WITHOUT_GRAV = 500 @@ -62,8 +63,8 @@ class SliderDriver extends Driver { } } - public constructor(constraint: Jolt.SliderConstraint, maxVelocity: number, info?: mirabuf.IInfo) { - super(info) + public constructor(id: DriverID, constraint: Jolt.SliderConstraint, maxVelocity: number, info?: mirabuf.IInfo) { + super(id, info) this._constraint = constraint this.maxVelocity = maxVelocity @@ -111,6 +112,16 @@ class SliderDriver extends Driver { this._constraint.SetTargetPosition(pos) } } + + public getReceiverType(): NoraTypes { + return NoraTypes.Number + } + public setReceiverValue(val: NoraNumber): void { + this.accelerationDirection = val + } + public DisplayName(): string { + return `${this.info?.name ?? "-"} [Slider]` + } } export default SliderDriver diff --git a/fission/src/systems/simulation/driver/WheelDriver.ts b/fission/src/systems/simulation/driver/WheelDriver.ts index 13b0420c8e..405694a194 100644 --- a/fission/src/systems/simulation/driver/WheelDriver.ts +++ b/fission/src/systems/simulation/driver/WheelDriver.ts @@ -1,8 +1,9 @@ import Jolt from "@barclah/jolt-physics" -import Driver from "./Driver" +import Driver, { DriverID } from "./Driver" import JOLT from "@/util/loading/JoltSyncLoader" import { SimType } from "../wpilib_brain/WPILibBrain" import { mirabuf } from "@/proto/mirabuf" +import { NoraNumber, NoraTypes } from "../Nora" const LATERIAL_FRICTION = 0.6 const LONGITUDINAL_FRICTION = 0.8 @@ -40,6 +41,7 @@ class WheelDriver extends Driver { } public constructor( + id: DriverID, constraint: Jolt.VehicleConstraint, maxVel: number, info?: mirabuf.IInfo, @@ -47,7 +49,7 @@ class WheelDriver extends Driver { device?: string, reversed: boolean = false ) { - super(info) + super(id, info) this._constraint = constraint this.maxVelocity = maxVel @@ -71,6 +73,16 @@ class WheelDriver extends Driver { public set reversed(val: boolean) { this._reversed = val } + + public getReceiverType(): NoraTypes { + return NoraTypes.Number + } + public setReceiverValue(val: NoraNumber): void { + this.accelerationDirection = val + } + public DisplayName(): string { + return `${this.info?.name ?? "-"} [Wheel]` + } } export default WheelDriver diff --git a/fission/src/systems/simulation/stimulus/ChassisStimulus.ts b/fission/src/systems/simulation/stimulus/ChassisStimulus.ts index 41d160dc6a..b06a55e0c5 100644 --- a/fission/src/systems/simulation/stimulus/ChassisStimulus.ts +++ b/fission/src/systems/simulation/stimulus/ChassisStimulus.ts @@ -1,7 +1,8 @@ import Jolt from "@barclah/jolt-physics" -import Stimulus from "./Stimulus" +import Stimulus, { StimulusID } from "./Stimulus" import World from "@/systems/World" import { mirabuf } from "@/proto/mirabuf" +import { NoraNumber3, NoraTypes } from "../Nora" class ChassisStimulus extends Stimulus { private _body: Jolt.Body @@ -20,14 +21,24 @@ class ChassisStimulus extends Stimulus { return this._body.GetRotation().GetEulerAngles() } - public constructor(bodyId: Jolt.BodyID, info?: mirabuf.IInfo) { - super(info) + public constructor(id: StimulusID, bodyId: Jolt.BodyID, info?: mirabuf.IInfo) { + super(id, info) this._body = World.PhysicsSystem.GetBody(bodyId) this._mass = this._body.GetShape().GetMassProperties().mMass } public Update(_: number): void {} + + public getSupplierType(): NoraTypes { + return NoraTypes.Number3 + } + public getSupplierValue(): NoraNumber3 { + throw new Error("Method not implemented.") + } + public DisplayName(): string { + return "Chassis [Accel|Gyro]" + } } export default ChassisStimulus diff --git a/fission/src/systems/simulation/stimulus/EncoderStimulus.ts b/fission/src/systems/simulation/stimulus/EncoderStimulus.ts index 6b88f5d7b0..b6806c11b7 100644 --- a/fission/src/systems/simulation/stimulus/EncoderStimulus.ts +++ b/fission/src/systems/simulation/stimulus/EncoderStimulus.ts @@ -1,12 +1,12 @@ import { mirabuf } from "@/proto/mirabuf" -import Stimulus from "./Stimulus" +import Stimulus, { StimulusID } from "./Stimulus" abstract class EncoderStimulus extends Stimulus { public abstract get positionValue(): number public abstract get velocityValue(): number - protected constructor(info?: mirabuf.IInfo) { - super(info) + protected constructor(id: StimulusID, info?: mirabuf.IInfo) { + super(id, info) } public abstract Update(_: number): void diff --git a/fission/src/systems/simulation/stimulus/HingeStimulus.ts b/fission/src/systems/simulation/stimulus/HingeStimulus.ts index b26dd7687d..4b22c59e39 100644 --- a/fission/src/systems/simulation/stimulus/HingeStimulus.ts +++ b/fission/src/systems/simulation/stimulus/HingeStimulus.ts @@ -1,6 +1,8 @@ import Jolt from "@barclah/jolt-physics" import EncoderStimulus from "./EncoderStimulus" import { mirabuf } from "@/proto/mirabuf" +import { StimulusID } from "./Stimulus" +import { NoraTypes, NoraNumber2 } from "../Nora" class HingeStimulus extends EncoderStimulus { private _accum: boolean = false @@ -26,8 +28,8 @@ class HingeStimulus extends EncoderStimulus { this._accum = shouldAccum } - public constructor(hinge: Jolt.HingeConstraint, info?: mirabuf.IInfo) { - super(info) + public constructor(id: StimulusID, hinge: Jolt.HingeConstraint, info?: mirabuf.IInfo) { + super(id, info) this._hinge = hinge } @@ -41,6 +43,16 @@ class HingeStimulus extends EncoderStimulus { public resetAccum() { this._hingeAngleAccum = 0.0 } + + public getSupplierType(): NoraTypes { + return NoraTypes.Number2 + } + public getSupplierValue(): NoraNumber2 { + return [this.positionValue, this.velocityValue] + } + public DisplayName(): string { + return `${this.info?.name ?? "-"} [Encoder]` + } } export default HingeStimulus diff --git a/fission/src/systems/simulation/stimulus/SliderStimulus.ts b/fission/src/systems/simulation/stimulus/SliderStimulus.ts index 3235256a25..9bb2aefdd4 100644 --- a/fission/src/systems/simulation/stimulus/SliderStimulus.ts +++ b/fission/src/systems/simulation/stimulus/SliderStimulus.ts @@ -1,6 +1,8 @@ import Jolt from "@barclah/jolt-physics" import EncoderStimulus from "./EncoderStimulus" import { mirabuf } from "@/proto/mirabuf" +import { StimulusID } from "./Stimulus" +import { NoraTypes, NoraNumber2 } from "../Nora" class SliderStimulus extends EncoderStimulus { private _slider: Jolt.SliderConstraint @@ -13,8 +15,8 @@ class SliderStimulus extends EncoderStimulus { return this._velocity } - public constructor(slider: Jolt.SliderConstraint, info?: mirabuf.IInfo) { - super(info) + public constructor(id: StimulusID, slider: Jolt.SliderConstraint, info?: mirabuf.IInfo) { + super(id, info) this._slider = slider } @@ -24,6 +26,16 @@ class SliderStimulus extends EncoderStimulus { this._velocity = (this._slider.GetCurrentPosition() - this._lastPosition) / deltaT this._lastPosition = this._slider.GetCurrentPosition() } + + public getSupplierType(): NoraTypes { + return NoraTypes.Number2 + } + public getSupplierValue(): NoraNumber2 { + return [this.positionValue, this.velocityValue] + } + public DisplayName(): string { + return `${this.info?.name ?? "-"} [Encoder]` + } } export default SliderStimulus diff --git a/fission/src/systems/simulation/stimulus/Stimulus.ts b/fission/src/systems/simulation/stimulus/Stimulus.ts index 9c5ab8758b..1d556c921d 100644 --- a/fission/src/systems/simulation/stimulus/Stimulus.ts +++ b/fission/src/systems/simulation/stimulus/Stimulus.ts @@ -1,17 +1,64 @@ import { mirabuf } from "@/proto/mirabuf" +import { MechanismConstraint } from "@/systems/physics/Mechanism" +import JOLT from "@/util/loading/JoltSyncLoader" +import { NoraType, NoraTypes } from "../Nora" +import { SimSupplier } from "../wpilib_brain/SimDataFlow" -abstract class Stimulus { +export enum StimulusType { + Stim_ChassisAccel = "Stim_ChassisAccel", + Stim_Encoder = "Stim_Encoder", + Stim_Unknown = "Stim_Unknown", +} + +export type StimulusID = { + type: StimulusType + name?: string + guid: string +} + +export function makeStimulusID(constraint: MechanismConstraint): StimulusID { + let stimulusType: StimulusType = StimulusType.Stim_Unknown + switch (constraint.constraint.GetSubType()) { + case JOLT.EConstraintSubType_Hinge: + case JOLT.EConstraintSubType_Slider: + case JOLT.EConstraintSubType_Vehicle: + stimulusType = StimulusType.Stim_Encoder + break + } + + return { + type: stimulusType, + name: constraint.info?.name ?? undefined, + guid: constraint.info?.GUID ?? "unknown", + } +} + +abstract class Stimulus implements SimSupplier { + private _id: StimulusID private _info?: mirabuf.IInfo - constructor(info?: mirabuf.IInfo) { + constructor(id: StimulusID, info?: mirabuf.IInfo) { + this._id = id this._info = info } public abstract Update(deltaT: number): void + public get id() { + return this._id + } + + public get idStr() { + return JSON.stringify(this._id) + } + public get info() { return this._info } + + public abstract getSupplierType(): NoraTypes + public abstract getSupplierValue(): NoraType + public abstract DisplayName(): string } export default Stimulus diff --git a/fission/src/systems/simulation/stimulus/WheelStimulus.ts b/fission/src/systems/simulation/stimulus/WheelStimulus.ts index 32214b5336..7c9fd51624 100644 --- a/fission/src/systems/simulation/stimulus/WheelStimulus.ts +++ b/fission/src/systems/simulation/stimulus/WheelStimulus.ts @@ -1,6 +1,8 @@ import Jolt from "@barclah/jolt-physics" import EncoderStimulus from "./EncoderStimulus" import { mirabuf } from "@/proto/mirabuf" +import { StimulusID } from "./Stimulus" +import { NoraTypes, NoraNumber2 } from "../Nora" /** * @@ -29,8 +31,8 @@ class WheelRotationStimulus extends EncoderStimulus { this._accum = shouldAccum } - public constructor(wheel: Jolt.Wheel, info?: mirabuf.IInfo) { - super(info) + public constructor(id: StimulusID, wheel: Jolt.Wheel, info?: mirabuf.IInfo) { + super(id, info) this._wheel = wheel } @@ -44,6 +46,16 @@ class WheelRotationStimulus extends EncoderStimulus { public resetAccum() { this._wheelRotationAccum = 0.0 } + + public getSupplierType(): NoraTypes { + return NoraTypes.Number2 + } + public getSupplierValue(): NoraNumber2 { + return [this.positionValue, this.velocityValue] + } + public DisplayName(): string { + return `${this.info?.name ?? "-"} [Encoder]` + } } export default WheelRotationStimulus diff --git a/fission/src/systems/simulation/synthesis_brain/SynthesisBrain.ts b/fission/src/systems/simulation/synthesis_brain/SynthesisBrain.ts index c98225cf58..4478bdba89 100644 --- a/fission/src/systems/simulation/synthesis_brain/SynthesisBrain.ts +++ b/fission/src/systems/simulation/synthesis_brain/SynthesisBrain.ts @@ -1,4 +1,3 @@ -import Mechanism from "@/systems/physics/Mechanism" import Brain from "../Brain" import Behavior from "../behavior/Behavior" import World from "@/systems/World" @@ -18,6 +17,9 @@ import PreferencesSystem from "@/systems/preferences/PreferencesSystem" import { DefaultSequentialConfig } from "@/systems/preferences/PreferenceTypes" import InputSystem from "@/systems/input/InputSystem" import MirabufSceneObject from "@/mirabuf/MirabufSceneObject" +import IntakeDriver from "../driver/IntakeDriver" +import EjectorDriver from "../driver/EjectorDriver" +import GamepieceManipBehavior from "../behavior/synthesis/GamepieceManipBehavior" class SynthesisBrain extends Brain { public static brainIndexMap = new Map() @@ -26,6 +28,7 @@ class SynthesisBrain extends Brain { private _simLayer: SimulationLayer private _assemblyName: string private _brainIndex: number + private _assembly: MirabufSceneObject // Tracks how many joins have been made with unique controls private _currentJointIndex = 1 @@ -58,10 +61,11 @@ class SynthesisBrain extends Brain { * @param mechanism The mechanism this brain will control. * @param assemblyName The name of the assembly that corresponds to the mechanism used for identification. */ - public constructor(mechanism: Mechanism, assemblyName: string) { - super(mechanism) + public constructor(assembly: MirabufSceneObject, assemblyName: string) { + super(assembly.mechanism, "synthesis") - this._simLayer = World.SimulationSystem.GetSimulationLayer(mechanism)! + this._assembly = assembly + this._simLayer = World.SimulationSystem.GetSimulationLayer(assembly.mechanism)! this._assemblyName = assemblyName // I'm not fixing this right now, but this is going to become an issue... @@ -74,10 +78,11 @@ class SynthesisBrain extends Brain { } // Only adds controls to mechanisms that are controllable (ignores fields) - if (mechanism.controllable) { + if (assembly.mechanism.controllable) { this.configureArcadeDriveBehavior() this.configureArmBehaviors() this.configureElevatorBehaviors() + this.configureGamepieceManipBehavior() } else { this.configureField() } @@ -87,9 +92,13 @@ class SynthesisBrain extends Brain { public Update(deltaT: number): void { this._behaviors.forEach(b => b.Update(deltaT)) + + this._assembly.ejectorActive = InputSystem.getInput("eject", this._brainIndex) > 0.5 + this._assembly.intakeActive = InputSystem.getInput("intake", this._brainIndex) > 0.5 } public Disable(): void { + this.clearControls() this._behaviors = [] } @@ -216,6 +225,22 @@ class SynthesisBrain extends Brain { } } + private configureGamepieceManipBehavior() { + let intake: IntakeDriver | undefined = undefined + let ejector: EjectorDriver | undefined = undefined + this._simLayer.drivers.forEach(x => { + if (x instanceof IntakeDriver) { + intake = x + } else if (x instanceof EjectorDriver) { + ejector = x + } + }) + + if (!intake || !ejector) return + + this._behaviors.push(new GamepieceManipBehavior(ejector, intake, this._brainIndex)) + } + /** Gets field preferences and handles any field specific configuration. */ private configureField() { PreferencesSystem.getFieldPreferences(this._assemblyName) diff --git a/fission/src/systems/simulation/wpilib_brain/SimDataFlow.ts b/fission/src/systems/simulation/wpilib_brain/SimDataFlow.ts new file mode 100644 index 0000000000..ab93391ded --- /dev/null +++ b/fission/src/systems/simulation/wpilib_brain/SimDataFlow.ts @@ -0,0 +1,70 @@ +import { NoraTypes, NoraType, NoraNumber } from "../Nora" + +export type SimSupplier = { + getSupplierType(): NoraTypes + getSupplierValue(): NoraType +} + +export type SimReceiver = { + getReceiverType(): NoraTypes + setReceiverValue(val: NoraType): void +} + +export type SimFlow = { + supplier: SimSupplier + receiver: SimReceiver +} + +export function validate(s: SimSupplier, r: SimReceiver): boolean { + return s.getSupplierType() === r.getReceiverType() +} + +export class SimSupplierAverage implements SimSupplier { + private _suppliers: SimSupplier[] + + public constructor(suppliers?: SimSupplier[]) { + if (!suppliers || suppliers.some(x => x.getSupplierType() != NoraTypes.Number)) { + this._suppliers = [] + } else { + this._suppliers = suppliers + } + } + + public AddSupplier(supplier: SimSupplier) { + if (supplier.getSupplierType() == NoraTypes.Number) { + this._suppliers.push(supplier) + } + } + + getSupplierType(): NoraTypes { + return NoraTypes.Number + } + getSupplierValue(): NoraNumber { + return this._suppliers.reduce((prev, next) => (prev += next.getSupplierValue() as NoraNumber), 0) + } +} + +export class SimReceiverDistribution implements SimReceiver { + private _receivers: SimReceiver[] + + public constructor(receivers?: SimReceiver[]) { + if (!receivers || receivers.some(x => x.getReceiverType() != NoraTypes.Number)) { + this._receivers = [] + } else { + this._receivers = receivers + } + } + + public AddReceiver(receiver: SimReceiver) { + if (receiver.getReceiverType() == NoraTypes.Number) { + this._receivers.push(receiver) + } + } + + getReceiverType(): NoraTypes { + return NoraTypes.Number + } + setReceiverValue(value: NoraNumber) { + this._receivers.forEach(x => x.setReceiverValue(value)) + } +} diff --git a/fission/src/systems/simulation/wpilib_brain/WPILibBrain.ts b/fission/src/systems/simulation/wpilib_brain/WPILibBrain.ts index 7fa35eddaf..122ed51eca 100644 --- a/fission/src/systems/simulation/wpilib_brain/WPILibBrain.ts +++ b/fission/src/systems/simulation/wpilib_brain/WPILibBrain.ts @@ -1,4 +1,3 @@ -import Mechanism from "@/systems/physics/Mechanism" import Brain from "../Brain" import Lazy from "@/util/Lazy.ts" @@ -9,6 +8,12 @@ import World from "@/systems/World" import { SimAnalogOutput, SimDigitalOutput, SimOutput } from "./SimOutput" import { SimAccelInput, SimAnalogInput, SimDigitalInput, SimGyroInput, SimInput } from "./SimInput" import { Random } from "@/util/Random" +import { NoraNumber, NoraNumber2, NoraNumber3, NoraTypes } from "../Nora" +import { SimFlow, SimReceiver, SimSupplier, validate } from "./SimDataFlow" +import MirabufSceneObject from "@/mirabuf/MirabufSceneObject" +import { SimConfig } from "@/ui/panels/simulation/SimConfigShared" +import SynthesisBrain from "../synthesis_brain/SynthesisBrain" +import PreferencesSystem from "@/systems/preferences/PreferencesSystem" const worker: Lazy = new Lazy(() => new WPILibWSWorker()) @@ -26,6 +31,8 @@ const CANMOTOR_BUS_VOLTAGE = ">busVoltage" const CANENCODER_POSITION = ">position" const CANENCODER_VELOCITY = ">velocity" +export let isConnected: boolean = false + export enum SimType { PWM = "PWM", SimDevice = "SimDevice", @@ -37,6 +44,7 @@ export enum SimType { DIO = "DIO", AI = "AI", AO = "AO", + DriverStation = "DriverStation", } enum FieldType { @@ -46,6 +54,42 @@ enum FieldType { Unknown = -1, } +export enum RobotSimMode { + Disabled = 0, + Teleop = 1, + Auto = 2, +} + +export type AllianceStation = "red1" | "red2" | "red3" | "blue1" | "blue2" | "blue3" + +export const supplierTypeMap: { [k in SimType]: NoraTypes | undefined } = { + [SimType.PWM]: NoraTypes.Number, + [SimType.SimDevice]: undefined, + [SimType.CANMotor]: NoraTypes.Number, + [SimType.Solenoid]: NoraTypes.Number, + [SimType.CANEncoder]: undefined, + [SimType.Gyro]: undefined, + [SimType.Accel]: undefined, + [SimType.DIO]: NoraTypes.Number, // ? + [SimType.AI]: undefined, + [SimType.AO]: NoraTypes.Number, + [SimType.DriverStation]: undefined, +} + +export const receiverTypeMap: { [k in SimType]: NoraTypes | undefined } = { + [SimType.PWM]: undefined, + [SimType.SimDevice]: undefined, + [SimType.CANMotor]: undefined, + [SimType.Solenoid]: undefined, + [SimType.CANEncoder]: NoraTypes.Number2, + [SimType.Gyro]: NoraTypes.Number3, // Wrong but its fine + [SimType.Accel]: NoraTypes.Number3, + [SimType.DIO]: NoraTypes.Number, // ? + [SimType.AI]: NoraTypes.Number, + [SimType.AO]: undefined, + [SimType.DriverStation]: undefined, +} + function GetFieldType(field: string): FieldType { if (field.length < 2) { return FieldType.Unknown @@ -64,7 +108,31 @@ function GetFieldType(field: string): FieldType { type DeviceName = string type DeviceData = Map -export const simMap = new Map>() +type SimMap = Map> +export const simMaps = new Map() + +let simBrain: WPILibBrain | undefined +export function setSimBrain(brain: WPILibBrain | undefined) { + if (brain && !simMaps.has(brain.assemblyName)) { + simMaps.set(brain.assemblyName, new Map()) + } + if (simBrain) worker.getValue().postMessage({ command: "disable" }) + simBrain = brain + if (simBrain) + worker.getValue().postMessage({ + command: "enable", + reconnect: PreferencesSystem.getGlobalPreference("SimAutoReconnect"), + }) +} + +export function hasSimBrain() { + return simBrain != undefined +} + +export function getSimMap(): SimMap | undefined { + if (!simBrain) return undefined + return simMaps.get(simBrain.assemblyName) +} export class SimGeneric { private constructor() {} @@ -78,41 +146,46 @@ export class SimGeneric { return undefined } - const map = simMap.get(simType) + const map = getSimMap()?.get(simType) if (!map) { - console.warn(`No '${simType}' devices found`) + // console.warn(`No '${simType}' devices found`) return undefined } const data = map.get(device) if (!data) { - console.warn(`No '${simType}' device '${device}' found`) + // console.warn(`No '${simType}' device '${device}' found`) return undefined } return (data.get(field) as T | undefined) ?? defaultValue } - public static Set(simType: SimType, device: string, field: string, value: T): boolean { + public static Set( + simType: SimType, + device: string, + field: string, + value: T + ): boolean { const fieldType = GetFieldType(field) if (fieldType != FieldType.Write && fieldType != FieldType.Both) { console.warn(`Field '${field}' is not a write or both field type`) return false } - const map = simMap.get(simType) + const map = getSimMap()?.get(simType) if (!map) { - console.warn(`No '${simType}' devices found`) + // console.warn(`No '${simType}' devices found`) return false } const data = map.get(device) if (!data) { - console.warn(`No '${simType}' device '${device}' found`) + // console.warn(`No '${simType}' device '${device}' found`) return false } - const selectedData: { [key: string]: number | boolean } = {} + const selectedData: { [key: string]: number | boolean | string } = {} selectedData[field] = value data.set(field, value) @@ -130,6 +203,27 @@ export class SimGeneric { } } +export class SimDriverStation { + private constructor() {} + + public static SetMatchTime(time: number) { + SimGeneric.Set(SimType.DriverStation, "", ">match_time", time) + } + + public static SetGameData(gameData: string) { + SimGeneric.Set(SimType.DriverStation, "", ">match_time", gameData) + } + + public static SetMode(mode: RobotSimMode) { + SimGeneric.Set(SimType.DriverStation, "", ">enabled", mode != RobotSimMode.Disabled) + SimGeneric.Set(SimType.DriverStation, "", ">autonomous", mode == RobotSimMode.Auto) + } + + public static SetStation(station: AllianceStation) { + SimGeneric.Set(SimType.DriverStation, "", ">station", station) + } +} + export class SimPWM { private constructor() {} @@ -140,6 +234,13 @@ export class SimPWM { public static GetPosition(device: string): number | undefined { return SimGeneric.Get(SimType.PWM, device, PWM_POSITION, 0.0) } + + public static GenSupplier(device: string): SimSupplier { + return { + getSupplierType: () => supplierTypeMap[SimType.PWM]!, + getSupplierValue: () => SimPWM.GetSpeed(device) ?? 0, + } + } } export class SimCAN { @@ -147,7 +248,9 @@ export class SimCAN { public static GetDeviceWithID(id: number, type: SimType): DeviceData | undefined { const id_exp = /SYN.*\[(\d+)\]/g - const entries = [...simMap.entries()].filter(([simType, _data]) => simType == type) + const map = getSimMap() + if (!map) return undefined + const entries = [...map.entries()].filter(([simType, _data]) => simType == type) for (const [_simType, data] of entries) { for (const key of data.keys()) { const result = [...key.matchAll(id_exp)] @@ -187,6 +290,13 @@ export class SimCANMotor { public static SetBusVoltage(device: string, voltage: number): boolean { return SimGeneric.Set(SimType.CANMotor, device, CANMOTOR_BUS_VOLTAGE, voltage) } + + public static GenSupplier(device: string): SimSupplier { + return { + getSupplierType: () => supplierTypeMap[SimType.CANMotor]!, + getSupplierValue: () => SimCANMotor.GetPercentOutput(device) ?? 0, + } + } } export class SimCANEncoder { private constructor() {} @@ -198,6 +308,16 @@ export class SimCANEncoder { public static SetPosition(device: string, position: number): boolean { return SimGeneric.Set(SimType.CANEncoder, device, CANENCODER_POSITION, position) } + + public static GenReceiver(device: string): SimReceiver { + return { + getReceiverType: () => receiverTypeMap[SimType.CANEncoder]!, + setReceiverValue: ([count, rate]: NoraNumber2) => { + SimCANEncoder.SetPosition(device, count) + SimCANEncoder.SetVelocity(device, rate) + }, + } + } } export class SimGyro { @@ -242,6 +362,17 @@ export class SimAccel { public static SetZ(device: string, accel: number): boolean { return SimGeneric.Set(SimType.Accel, device, ">z", accel) } + + public static GenReceiver(device: string): SimReceiver { + return { + getReceiverType: () => receiverTypeMap[SimType.Accel]!, + setReceiverValue: ([x, y, z]: NoraNumber3) => { + SimAccel.SetX(device, x) + SimAccel.SetY(device, y) + SimAccel.SetZ(device, z) + }, + } + } } export class SimDIO { @@ -254,6 +385,22 @@ export class SimDIO { public static GetValue(device: string): boolean { return SimGeneric.Get(SimType.DIO, device, "<>value", false) } + + public static GenReceiver(device: string): SimReceiver { + return { + getReceiverType: () => receiverTypeMap[SimType.DIO]!, + setReceiverValue: (a: NoraNumber) => { + SimDIO.SetValue(device, a > 0.5) + }, + } + } + + public static GenSupplier(device: string): SimSupplier { + return { + getSupplierType: () => receiverTypeMap[SimType.DIO]!, + getSupplierValue: () => (SimDIO.GetValue(device) ? 1 : 0), + } + } } export class SimAI { @@ -330,6 +477,21 @@ type WSMessage = { worker.getValue().addEventListener("message", (eventData: MessageEvent) => { let data: WSMessage | undefined + if (eventData.data.status) { + switch (eventData.data.status) { + case "open": + isConnected = true + break + case "close": + case "error": + isConnected = false + break + default: + return + } + return + } + if (typeof eventData.data == "object") { data = eventData.data } else { @@ -347,6 +509,8 @@ worker.getValue().addEventListener("message", (eventData: MessageEvent) => { }) function UpdateSimMap(type: SimType, device: string, updateData: DeviceData) { + const simMap = getSimMap() + if (!simMap) return let typeMap = simMap.get(type) if (!typeMap) { typeMap = new Map() @@ -366,26 +530,42 @@ function UpdateSimMap(type: SimType, device: string, updateData: DeviceData) { class WPILibBrain extends Brain { private _simLayer: SimulationLayer + private _assembly: MirabufSceneObject private _simOutputs: SimOutput[] = [] private _simInputs: SimInput[] = [] + private _simFlows: SimFlow[] = [] + + public get assemblyName() { + return this._assembly.assemblyName + } + + constructor(assembly: MirabufSceneObject) { + super(assembly.mechanism, "wpilib") - constructor(mechanism: Mechanism) { - super(mechanism) + this._assembly = assembly - this._simLayer = World.SimulationSystem.GetSimulationLayer(mechanism)! + this._simLayer = World.SimulationSystem.GetSimulationLayer(this._mechanism)! if (!this._simLayer) { console.warn("SimulationLayer is undefined") return } - this.addSimInput(new SimGyroInput("Test Gyro[1]", mechanism)) - this.addSimInput(new SimAccelInput("ADXL362[4]", mechanism)) + this.addSimInput(new SimGyroInput("Test Gyro[1]", this._mechanism)) + this.addSimInput(new SimAccelInput("ADXL362[4]", this._mechanism)) this.addSimInput(new SimDigitalInput("SYN DI[0]", () => Random() > 0.5)) this.addSimOutput(new SimDigitalOutput("SYN DO[1]")) this.addSimInput(new SimAnalogInput("SYN AI[0]", () => Random() * 12)) this.addSimOutput(new SimAnalogOutput("SYN AO[1]")) + + this.loadSimConfig() + + World.SceneRenderer.sceneObjects.forEach(v => { + if (v instanceof MirabufSceneObject && v.brain?.brainType == "wpilib") { + v.brain = new SynthesisBrain(v, v.assemblyName) + } + }) } public addSimOutput(device: SimOutput) { @@ -396,17 +576,55 @@ class WPILibBrain extends Brain { this._simInputs.push(input) } + public addSimFlow(flow: SimFlow): boolean { + if (validate(flow.supplier, flow.receiver)) { + this._simFlows.push(flow) + return true + } + return false + } + + public loadSimConfig(): boolean { + this._simFlows = [] + const configData = this._assembly.simConfigData + if (!configData) return false + + const flows = SimConfig.Compile(configData, this._assembly) + if (!flows) { + console.error(`Failed to compile saved simulation configuration data for '${this.assemblyName}'`) + return false + } + + let counter = 0 + flows.forEach(x => { + if (!this.addSimFlow(x)) { + console.debug("Failed to validate flow, skipping...") + } else { + counter++ + } + }) + console.debug(`${counter} Flows added!`) + return true + } + public Update(deltaT: number): void { this._simOutputs.forEach(d => d.Update(deltaT)) this._simInputs.forEach(i => i.Update(deltaT)) + this._simFlows.forEach(({ supplier, receiver }) => { + receiver.setReceiverValue(supplier.getSupplierValue()) + }) } public Enable(): void { - worker.getValue().postMessage({ command: "connect" }) + setSimBrain(this) + // worker.getValue().postMessage({ command: "enable", reconnect: RECONNECT }) } public Disable(): void { - worker.getValue().postMessage({ command: "disconnect" }) + if (simBrain == this) { + setSimBrain(undefined) + } + // worker.getValue().postMessage({ command: "disable" }) } } diff --git a/fission/src/systems/simulation/wpilib_brain/WPILibWSWorker.ts b/fission/src/systems/simulation/wpilib_brain/WPILibWSWorker.ts index 1da08a1b75..49dca0465b 100644 --- a/fission/src/systems/simulation/wpilib_brain/WPILibWSWorker.ts +++ b/fission/src/systems/simulation/wpilib_brain/WPILibWSWorker.ts @@ -4,7 +4,19 @@ let socket: WebSocket | undefined = undefined const connectMutex = new Mutex() -async function tryConnect(port: number | undefined): Promise { +let intervalHandle: NodeJS.Timeout | undefined = undefined +let reconnect = false +const RECONNECT_INTERVAL = 1000 + +function socketOpen(): boolean { + return (socket && socket.readyState == WebSocket.OPEN) ?? false +} + +function socketConnecting(): boolean { + return (socket && socket.readyState == WebSocket.CONNECTING) ?? false +} + +async function tryConnect(port?: number): Promise { await connectMutex .runExclusive(() => { if ((socket?.readyState ?? WebSocket.CLOSED) == WebSocket.OPEN) { @@ -21,6 +33,9 @@ async function tryConnect(port: number | undefined): Promise { console.log("WS Could not open") self.postMessage({ status: "error" }) }) + socket.addEventListener("close", () => { + self.postMessage({ status: "close" }) + }) socket.addEventListener("message", onMessage) }) @@ -44,17 +59,39 @@ function onMessage(event: MessageEvent) { // Sends outgoing messages self.addEventListener("message", e => { switch (e.data.command) { - case "connect": - tryConnect(e.data.port) + case "enable": { + reconnect = e.data.reconnect ?? false + const intervalFunc = () => { + if (intervalHandle != undefined && !socketOpen() && !socketConnecting()) { + tryConnect() + } + + if (!reconnect) { + clearInterval(intervalHandle) + intervalHandle = undefined + } + } + if (intervalHandle != undefined) { + clearInterval(intervalHandle) + } + intervalHandle = setInterval(intervalFunc, RECONNECT_INTERVAL) break - case "disconnect": + } + case "disable": { + clearInterval(intervalHandle) + intervalHandle = undefined tryDisconnect() break - case "update": - if (socket) socket.send(JSON.stringify(e.data.data)) + } + case "update": { + if (socketOpen()) { + socket!.send(JSON.stringify(e.data.data)) + } break - default: + } + default: { console.warn(`Unrecognized command '${e.data.command}'`) break + } } }) diff --git a/fission/src/test/ui/SelectMenu.test.tsx b/fission/src/test/ui/SelectMenu.test.tsx index da361139ec..537345bc1d 100644 --- a/fission/src/test/ui/SelectMenu.test.tsx +++ b/fission/src/test/ui/SelectMenu.test.tsx @@ -14,7 +14,7 @@ class ConfigModeSelectionOption extends SelectMenuOption { configMode: ConfigMode constructor(name: string, configMode: ConfigMode) { - super(name) + super(name, name) this.configMode = configMode } } diff --git a/fission/src/ui/components/BespokeGraph.tsx b/fission/src/ui/components/BespokeGraph.tsx new file mode 100644 index 0000000000..5f983a9feb --- /dev/null +++ b/fission/src/ui/components/BespokeGraph.tsx @@ -0,0 +1,525 @@ +/** + * This was originally written before using ReactFlow for the node editor. + * It's mostly working (missing some interaction aspects) and does some + * interesting work with SVGs that I think would be really useful for a + * more advance 2D overlay for directing the users attention to key points + * in the 3D scene. + */ + +import { DOMUnitExpression } from "@/util/Units" +import { useCallback, useEffect, useMemo, useReducer, useRef } from "react" +import { colorNameToVar } from "../ThemeContext" + +const DEBUG_EDGE_CONTROL_LINES = false + +const EDGE_FLAT = 0.1 +const EDGE_CURVE = 0.3 +const EDGE_CURVE_MIN = DOMUnitExpression.fromUnit(2, "rem") +const NODE_SIZE = DOMUnitExpression.fromUnit(0.5, "rem") +const EDGE_FLAT_MAX = NODE_SIZE.mul(DOMUnitExpression.fromUnit(Math.SQRT2)).add(DOMUnitExpression.fromUnit(1, "rem")) +const NODE_LABEL_Y_OFFSET = NODE_SIZE.add(DOMUnitExpression.fromUnit(0.325, "rem")) +const JUNCTION_SIZE = NODE_SIZE.add(DOMUnitExpression.fromUnit(0.125, "rem")) +const MODULE_HEIGHT = DOMUnitExpression.fromUnit(1, "h").sub(DOMUnitExpression.fromUnit(0.125, "rem")) +const MODULE_HEIGHT_HALF = MODULE_HEIGHT.div(DOMUnitExpression.fromUnit(2)) +const MODULE_SPAN_Y = MODULE_HEIGHT.sub(DOMUnitExpression.fromUnit(4, "rem")) +const MODULE_SPAN_Y_HALF = MODULE_SPAN_Y.div(DOMUnitExpression.fromUnit(2, "px")) +const MODULE_NODE_OFFSET = DOMUnitExpression.fromUnit(6, "rem") +const MODULE_CORNER_RADIUS = DOMUnitExpression.fromUnit(1, "rem") + +type NodeDirection = "in" | "out" + +let nextId = 0 + +class Node { + public x: DOMUnitExpression + public y: DOMUnitExpression + public label?: string + public direction: NodeDirection + private _id: string + + public get id() { + return this._id + } + + public constructor( + id: string, + direction: NodeDirection, + label?: string, + x?: DOMUnitExpression, + y?: DOMUnitExpression + ) { + this.direction = direction + this._id = id + this.x = x ?? DOMUnitExpression.fromUnit(0) + this.y = y ?? DOMUnitExpression.fromUnit(0) + this.label = label + } +} + +class Junction { + private _x: DOMUnitExpression + private _y: DOMUnitExpression + + private _id: number + + public graph: Graph + + private _nodeIn: Node + private _nodeOut: Node + + public get x() { + return this._x + } + public get y() { + return this._y + } + + public get id() { + return this._id + } + + public get nodeIn() { + return this._nodeIn + } + public get nodeOut() { + return this._nodeOut + } + + public get nodeIdIn() { + return this._nodeIn.id + } + public get nodeIdOut() { + return this._nodeOut.id + } + + public set x(val: DOMUnitExpression) { + this._x = val + this.updateNodes() + } + public set y(val: DOMUnitExpression) { + this._y = val + this.updateNodes() + } + + public constructor(graph: Graph, x?: DOMUnitExpression, y?: DOMUnitExpression) { + this.graph = graph + this._id = nextId++ + this._x = x ?? DOMUnitExpression.fromUnit(0) + this._y = y ?? DOMUnitExpression.fromUnit(0) + this._nodeIn = graph.createNode(`junct_in_${this._id}`, "in") + this._nodeOut = graph.createNode(`junct_out_${this._id}`, "out") + this.updateNodes() + } + + private updateNodes() { + this._nodeIn.x = this._x.sub(JUNCTION_SIZE) + this._nodeIn.y = this._y + this._nodeOut.x = this._x.add(JUNCTION_SIZE) + this._nodeOut.y = this._y + + // console.debug(`${this._nodeIn.x.toFixed(1)} ${this._nodeIn.y.toFixed(1)}`) + } +} + +function EdgeComp({ from, to, graph, element }: { from: string; to: string; graph: Graph; element: Element }) { + const [nodeFrom, nodeTo] = useMemo(() => [graph.nodes.get(from)!, graph.nodes.get(to)!], [from, graph, to]) + + const [fromX, fromY] = [nodeFrom.x.evaluate(element), nodeFrom.y.evaluate(element)] + const [toX, toY] = [nodeTo.x.evaluate(element), nodeTo.y.evaluate(element)] + const spanX = Math.abs(toX - fromX) + + const flatMax = EDGE_FLAT_MAX.evaluate(element) + const flat = Math.min(spanX * EDGE_FLAT, flatMax) + const curveMin = EDGE_CURVE_MIN.evaluate(element) + const curve = Math.max(spanX * EDGE_CURVE, curveMin) + + const cmds = ` + M ${fromX} ${fromY} + h ${flat} + C ${fromX + flat + curve},${fromY} ${toX - flat - curve},${toY} ${toX - flat},${toY} + L ${toX} ${toY} + ` + + const debugCmds = ` + M ${fromX + flat} ${fromY} + L ${fromX + flat + curve},${fromY} ${toX - flat - curve},${toY} ${toX - flat},${toY} + ` + + // const cmds = ` + // M ${fromX} ${fromY} + // h ${flatSign * EDGE_FLAT.evaluate(element)} + // c ${flatSign * spanX * EDGE_CURVE},0 ${spanX * (1 - (2 * flatSign * EDGE_FLAT) - flatSign * EDGE_CURVE)},${spanY} ${spanX * (1 - 2 * flatSign * EDGE_FLAT)},${spanY} + // h ${flatSign * spanX * EDGE_FLAT} + // ` + + return ( + + + {DEBUG_EDGE_CONTROL_LINES ? ( + + ) : ( + <> + )} + + ) +} + +function JunctionComp({ junct, element }: { junct: Junction; element: Element }) { + return ( + <> + + + ) +} + +function NodeComp({ node, graph, element }: { node: Node; graph: Graph; element: Element }) { + const { label, direction } = node + const x = node.x.evaluate(element) + const y = node.y.evaluate(element) + + const nodeSize = NODE_SIZE.evaluate(element) + const nodeLabelOffset = NODE_LABEL_Y_OFFSET.evaluate(element) + + const onClick = useCallback( + (_: React.MouseEvent) => { + console.debug(`Clicked node: ${node.label ? node.label : `${x.toFixed(1)}, ${y.toFixed(1)}`}`) + }, + [node.label, x, y] + ) + + const pathCmds = + direction === "in" + ? ` + M ${x - Math.SQRT2 * nodeSize} ${y} + l ${nodeSize / Math.SQRT2} ${-(nodeSize / Math.SQRT2)} + a ${nodeSize} ${nodeSize} 270 1 1 0 ${2 * (nodeSize / Math.SQRT2)} + Z + ` + : ` + M ${x + Math.SQRT2 * nodeSize} ${y} + l ${-(nodeSize / Math.SQRT2)} ${-(nodeSize / Math.SQRT2)} + a ${nodeSize} ${nodeSize} 270 1 0 0 ${2 * (nodeSize / Math.SQRT2)} + Z + ` + + return ( + + 0 ? colorNameToVar("InteractiveElementSolid") : "white" + } + /> + {label ? ( + + {label} + + ) : ( + <> + )} + + ) +} + +class Module { + private _inNodes: string[] + private _outNodes: string[] + + private _id: number + + public x: DOMUnitExpression + public y: DOMUnitExpression + + public graph: Graph + + public get inNodes() { + return this._inNodes + } + public get outNodes() { + return this._outNodes + } + + public get id() { + return this._id + } + + public constructor( + graph: Graph, + inNodes: { id: string; label: string }[], + outNodes: { id: string; label: string }[], + x?: DOMUnitExpression, + y?: DOMUnitExpression + ) { + this.graph = graph + this._id = nextId++ + this.x = x ?? DOMUnitExpression.fromUnit(0.5, "w") + this.y = y ?? DOMUnitExpression.fromUnit(0.5, "h") + this._inNodes = [] + this._outNodes = [] + + inNodes.forEach((x, i) => { + const y = MODULE_SPAN_Y.mul(DOMUnitExpression.fromUnit((i + 1) / (inNodes.length + 1), "px")) + const node = graph.createNode( + x.id, + "in", + x.label, + this.x.sub(MODULE_NODE_OFFSET), + this.y.sub(MODULE_SPAN_Y_HALF).add(y) + ) + this._inNodes.push(node.id) + }) + outNodes.forEach((x, i) => { + const y = MODULE_SPAN_Y.mul(DOMUnitExpression.fromUnit((i + 1) / (outNodes.length + 1), "px")) + const node = graph.createNode( + x.id, + "out", + x.label, + this.x.add(MODULE_NODE_OFFSET), + this.y.sub(MODULE_SPAN_Y_HALF).add(y) + ) + this._outNodes.push(node.id) + }) + } +} + +function ModuleComp({ module, element }: { module: Module; element: Element }) { + const x = module.x.evaluate(element) + const y = module.y.evaluate(element) + + const heightHalf = MODULE_HEIGHT_HALF.evaluate(element) + const widthHalf = MODULE_NODE_OFFSET.evaluate(element) + const cornerRad = MODULE_CORNER_RADIUS.evaluate(element) + + const cmds = + module.inNodes.length != 0 && module.outNodes.length != 0 + ? ` + M ${x - widthHalf} ${y - heightHalf + cornerRad} + A ${cornerRad} ${cornerRad} 90 0 1 ${x - widthHalf + cornerRad} ${y - heightHalf} + L ${x + widthHalf - cornerRad} ${y - heightHalf} + A ${cornerRad} ${cornerRad} 90 0 1 ${x + widthHalf} ${y - heightHalf + cornerRad} + L ${x + widthHalf} ${y + heightHalf - cornerRad} + A ${cornerRad} ${cornerRad} 90 0 1 ${x + widthHalf - cornerRad} ${y + heightHalf} + L ${x - widthHalf + cornerRad} ${y + heightHalf} + A ${cornerRad} ${cornerRad} 90 0 1 ${x - widthHalf} ${y + heightHalf - cornerRad} + Z + ` + : module.inNodes.length == 0 && module.outNodes.length != 0 + ? ` + M ${x} ${y - heightHalf} + L ${x + widthHalf - cornerRad} ${y - heightHalf} + A ${cornerRad} ${cornerRad} 90 0 1 ${x + widthHalf} ${y - heightHalf + cornerRad} + L ${x + widthHalf} ${y + heightHalf - cornerRad} + A ${cornerRad} ${cornerRad} 90 0 1 ${x + widthHalf - cornerRad} ${y + heightHalf} + L ${x} ${y + heightHalf} + ` + : module.outNodes.length == 0 && module.inNodes.length != 0 + ? ` + M ${x} ${y - heightHalf} + L ${x - widthHalf + cornerRad} ${y - heightHalf} + A ${cornerRad} ${cornerRad} 90 0 0 ${x - widthHalf} ${y - heightHalf + cornerRad} + L ${x - widthHalf} ${y + heightHalf - cornerRad} + A ${cornerRad} ${cornerRad} 90 0 0 ${x - widthHalf + cornerRad} ${y + heightHalf} + L ${x} ${y + heightHalf} + ` + : "" + + return ( + <> + + + ) +} + +export class Graph { + private _nodes: Map + private _juncts: Map + private _edges: Map + private _adjacency: Map> + private _modules: Module[] + + public get nodes() { + return this._nodes + } + public get juncts() { + return this._juncts + } + public get edges() { + return this._edges + } + public get modules() { + return this._modules + } + public get adjacency() { + return this._adjacency + } + + public constructor() { + this._nodes = new Map() + this._juncts = new Map() + this._edges = new Map() + this._adjacency = new Map>() + this._modules = [] + } + + public createNode( + id: string, + direction: NodeDirection, + label?: string, + x?: DOMUnitExpression, + y?: DOMUnitExpression + ): Node { + const node = new Node(id, direction, label, x, y) + this._nodes.set(id, node) + this._adjacency.set(id, new Set()) + return node + } + + public createJunction(x?: DOMUnitExpression, y?: DOMUnitExpression): Junction { + const junct = new Junction(this, x, y) + this._juncts.set(junct.id, junct) + return junct + } + + public createEdge(nodeA: string, nodeB: string) { + const edgeId = nextId++ + const a = this._nodes.get(nodeA) + const b = this._nodes.get(nodeB) + if (!(a && b)) { + throw new Error("Nodes not found") + } + if (a.direction === b.direction) { + throw new Error("Incompatible directions") + } + if (a.direction === "out") { + this._edges.set(edgeId, { from: nodeA, to: nodeB }) + } else { + this._edges.set(edgeId, { from: nodeB, to: nodeA }) + } + this._adjacency.get(nodeA)!.add(edgeId) + this._adjacency.get(nodeB)!.add(edgeId) + } + + public createModule( + inNodes: { id: string; label: string }[], + outNodes: { id: string; label: string }[], + x?: DOMUnitExpression, + y?: DOMUnitExpression + ): Module { + const module = new Module(this, inNodes, outNodes, x, y) + this._modules.push(module) + return module + } + + public removeEdge(edgeId: number): boolean { + const edge = this._edges.get(edgeId) + if (!edge) { + return false + } + return ( + (this._adjacency.get(edge.from)?.delete(edgeId) ?? false) && + (this._adjacency.get(edge.to)?.delete(edgeId) ?? false) && + this._edges.delete(edgeId) + ) + } + + public disconnectNode(nodeA: string): boolean { + const adjEdges = new Set(this._adjacency.get(nodeA)) + if (!adjEdges) { + return false + } + return [...adjEdges].reduce((prev, curr) => prev && this.removeEdge(curr), true) + } + + public removeNode(nodeA: string): boolean { + if (!this._nodes.has(nodeA)) { + return false + } + return this.disconnectNode(nodeA) && this._nodes.delete(nodeA) + } +} + +function GraphComp({ graph }: { graph: Graph }) { + const svgRef = useRef(null) + + const [renderHook, forceRenderer] = useReducer(x => !x, false) + + useEffect(() => { + const anim = () => { + forceRenderer() + + cancelAnimationFrame(handle) + handle = requestAnimationFrame(anim) + } + + let handle = requestAnimationFrame(anim) + + return () => { + cancelAnimationFrame(handle) + } + }, []) + + const comps = useMemo(() => { + return svgRef.current != null ? ( + <> + {graph.modules.map(x => ( + + ))} + {[...graph.edges.values()].map(x => ( + + ))} + {[...graph.juncts.values()].map(x => ( + + ))} + {[...graph.nodes.values()].map(x => ( + + ))} + + ) : ( + <> + ) + // eslint-disable-next-line react-hooks/exhaustive-deps + }, [renderHook, graph]) + + return ( + + {comps} + + ) +} + +export default GraphComp diff --git a/fission/src/ui/components/Panel.tsx b/fission/src/ui/components/Panel.tsx index bed0ec4fa6..06399c4ed7 100644 --- a/fission/src/ui/components/Panel.tsx +++ b/fission/src/ui/components/Panel.tsx @@ -93,6 +93,7 @@ type PanelProps = { children?: ReactNode className?: string contentClassName?: string + full?: boolean } const Panel: React.FC = ({ @@ -116,16 +117,21 @@ const Panel: React.FC = ({ acceptBlocked = false, className, contentClassName, + full = false, }) => { const { closePanel } = usePanelControlContext() const iconEl: ReactNode = typeof icon === "string" ? Icon : icon openLocation ||= "center" sidePadding ||= 16 const locationClasses = getLocationClasses(openLocation, sidePadding) + + const mainSizing = full ? "left-5 right-5 top-5 bottom-5" : "max-h-[95vh] max-w-[50vw]" + const contentSizing = full ? "grow" : "max-h-[75vh]" + return (
@@ -149,7 +155,7 @@ const Panel: React.FC = ({ id="content" className={`${contentClassName || ""} ${ !contentClassName?.includes("mx") ? "mx-[2rem]" : "" - } flex flex-col gap-4 max-h-[75vh]`} + } relative flex flex-col gap-4 ${contentSizing}`} > {children}
diff --git a/fission/src/ui/components/SelectMenu.tsx b/fission/src/ui/components/SelectMenu.tsx index d266208d13..8efcd5ea35 100644 --- a/fission/src/ui/components/SelectMenu.tsx +++ b/fission/src/ui/components/SelectMenu.tsx @@ -44,9 +44,11 @@ const CustomButton = styled(MUIButton)({ /** Extend this to make a type that contains custom data */ export class SelectMenuOption { + id: string name: string tooltipText?: string - constructor(name: string, tooltipText?: string) { + constructor(id: string, name: string, tooltipText?: string) { + this.id = id this.name = name this.tooltipText = tooltipText } @@ -169,7 +171,7 @@ const SelectMenu: React.FC = ({ // If the selected option no longer exists as an option, deselect it useEffect(() => { - if (selectedOption && !options.some(o => o.name === selectedOption.name)) { + if (selectedOption && !options.some(o => o.id === selectedOption.id)) { setSelectedOption(undefined) onOptionSelected(undefined) } diff --git a/fission/src/ui/components/WPILibConnectionStatus.tsx b/fission/src/ui/components/WPILibConnectionStatus.tsx new file mode 100644 index 0000000000..fc304d3d98 --- /dev/null +++ b/fission/src/ui/components/WPILibConnectionStatus.tsx @@ -0,0 +1,30 @@ +import { useEffect, useState } from "react" +import Label, { LabelSize } from "./Label" +import { hasSimBrain, isConnected } from "@/systems/simulation/wpilib_brain/WPILibBrain" +import { FaCheck, FaXmark } from "react-icons/fa6" + +export default function WPILibConnectionStatus() { + const [status, setStatus] = useState(false) + const [enabled, setEnabled] = useState(false) + + useEffect(() => { + const handle = setInterval(() => { + setEnabled(hasSimBrain()) + setStatus(isConnected) + }, 500) + return () => clearInterval(handle) + }, []) + + return enabled ? ( +
+ {status ? ( + + ) : ( + + )} + +
+ ) : ( + <> + ) +} diff --git a/fission/src/ui/modals/configuring/rio-config/RCConfigCANGroupModal.tsx b/fission/src/ui/modals/configuring/rio-config/RCConfigCANGroupModal.tsx index b2a1641d08..bd9c27dc18 100644 --- a/fission/src/ui/modals/configuring/rio-config/RCConfigCANGroupModal.tsx +++ b/fission/src/ui/modals/configuring/rio-config/RCConfigCANGroupModal.tsx @@ -7,7 +7,7 @@ import Checkbox from "@/components/Checkbox" import Container from "@/components/Container" import Label, { LabelSize } from "@/components/Label" import Input from "@/components/Input" -import WPILibBrain, { simMap, SimType } from "@/systems/simulation/wpilib_brain/WPILibBrain" +import WPILibBrain, { getSimMap, SimType } from "@/systems/simulation/wpilib_brain/WPILibBrain" import { CANOutputGroup } from "@/systems/simulation/wpilib_brain/SimOutput" import World from "@/systems/World" import MirabufSceneObject from "@/mirabuf/MirabufSceneObject" @@ -32,7 +32,7 @@ const RCConfigCANGroupModal: React.FC = ({ modalId }) => { brain = simLayer?.brain as WPILibBrain } - const cans = simMap.get(SimType.CANMotor) ?? new Map>() + const cans = getSimMap()?.get(SimType.CANMotor) ?? new Map>() const devices: [string, Map][] = [...cans.entries()] .filter(([_, data]) => data.get(" = ({ modalId }) => { brain = simLayer?.brain as WPILibBrain } - const devices: [string, unknown][] = [...(simMap.get(SimType.CANEncoder)?.entries() ?? [])] // ugly + const devices: [string, unknown][] = [...(getSimMap()?.get(SimType.CANEncoder)?.entries() ?? [])] // ugly const stimMap = new Map() diff --git a/fission/src/ui/modals/configuring/rio-config/RCConfigPWMGroupModal.tsx b/fission/src/ui/modals/configuring/rio-config/RCConfigPWMGroupModal.tsx index 3a227dc4a2..c6445cac5b 100644 --- a/fission/src/ui/modals/configuring/rio-config/RCConfigPWMGroupModal.tsx +++ b/fission/src/ui/modals/configuring/rio-config/RCConfigPWMGroupModal.tsx @@ -7,7 +7,7 @@ import Checkbox from "@/components/Checkbox" import Container from "@/components/Container" import Label, { LabelSize } from "@/components/Label" import Input from "@/components/Input" -import WPILibBrain, { simMap } from "@/systems/simulation/wpilib_brain/WPILibBrain" +import WPILibBrain, { getSimMap } from "@/systems/simulation/wpilib_brain/WPILibBrain" import { PWMOutputGroup } from "@/systems/simulation/wpilib_brain/SimOutput" import World from "@/systems/World" import MirabufSceneObject from "@/mirabuf/MirabufSceneObject" @@ -34,7 +34,7 @@ const RCConfigPWMGroupModal: React.FC = ({ modalId }) => { } let devices: [string, unknown][] = [] - const pwms = simMap.get(SimType.PWM) + const pwms = getSimMap()?.get(SimType.PWM) if (pwms) { devices = [...pwms.entries()].filter(([_, data]) => data.get(" = ({ modalId }) => { const mechanism = (miraObjs[0][1] as MirabufSceneObject).mechanism const simLayer = World.SimulationSystem.GetSimulationLayer(mechanism) console.log("simlayer", simLayer) - if (!(simLayer?.brain instanceof WPILibBrain)) simLayer?.SetBrain(new WPILibBrain(mechanism)) + if (!(simLayer?.brain instanceof WPILibBrain)) + simLayer?.SetBrain(new WPILibBrain(miraObjs[0][1] as MirabufSceneObject)) } switch (type) { case "PWM": diff --git a/fission/src/ui/panels/DebugPanel.tsx b/fission/src/ui/panels/DebugPanel.tsx index 9d1a7bedab..3e39edbc34 100644 --- a/fission/src/ui/panels/DebugPanel.tsx +++ b/fission/src/ui/panels/DebugPanel.tsx @@ -2,7 +2,6 @@ import Panel, { PanelPropsImpl } from "../components/Panel" import Button from "../components/Button" import World from "@/systems/World" import MirabufSceneObject from "@/mirabuf/MirabufSceneObject" -import WPILibBrain from "@/systems/simulation/wpilib_brain/WPILibBrain" import { ToastType } from "../ToastContext" import { Random } from "@/util/Random" import MirabufCachingService, { @@ -19,7 +18,6 @@ import Jolt from "@barclah/jolt-physics" import Label from "../components/Label" import { colorNameToVar } from "../ThemeContext" import { SynthesisIcons } from "../components/StyledComponents" -import { useModalControlContext } from "../ModalContext" import { Global_AddToast } from "../components/GlobalUIControls" const LabelStyled = styled(Label)({ @@ -55,7 +53,6 @@ async function TestGodMode() { const DebugPanel: React.FC = ({ panelId }) => { const { openPanel } = usePanelControlContext() - const { openModal } = useModalControlContext() return ( = ({ panelId }) => { /> Code Simulation - + ) +} + +function FlowControls({ onCreateJunction }: FlowControlsProps) { + const { zoomIn, zoomOut, fitView } = useReactFlow() + + return ( + + + + + + + + + + + + + + + ) +} + +export default FlowControls diff --git a/fission/src/ui/panels/simulation/FlowInfo.tsx b/fission/src/ui/panels/simulation/FlowInfo.tsx new file mode 100644 index 0000000000..2b680abfd2 --- /dev/null +++ b/fission/src/ui/panels/simulation/FlowInfo.tsx @@ -0,0 +1,15 @@ +import { Panel as FlowPanel } from "@xyflow/react" +import { CustomTooltip, RefreshButton } from "@/ui/components/StyledComponents" + +function FlowInfo({ reset }: { reset: () => void }) { + return ( + + {CustomTooltip( + "Click and drag to make connection to your robot's IO. Use the controls in the bottom left to zoom in/out, fit to the nodes in the graph, and add junction nodes for an easier experience connecting many motors to many joints. Holding ALT while dropping an edge over nothing will break out the edge into it's separate components, if it has multiple. Click the reset button to the left to completely reset all the wiring nodes" + )} + {RefreshButton(reset)} + + ) +} + +export default FlowInfo diff --git a/fission/src/ui/panels/simulation/SimConfigShared.ts b/fission/src/ui/panels/simulation/SimConfigShared.ts new file mode 100644 index 0000000000..4358f68c21 --- /dev/null +++ b/fission/src/ui/panels/simulation/SimConfigShared.ts @@ -0,0 +1,835 @@ +import MirabufSceneObject from "@/mirabuf/MirabufSceneObject" +import Driver, { DriverType } from "@/systems/simulation/driver/Driver" +import { + deconstructNoraType, + hasNoraAverageFunc, + noraAverageFunc, + NoraType, + NoraTypes, +} from "@/systems/simulation/Nora" +import Stimulus, { StimulusType } from "@/systems/simulation/stimulus/Stimulus" +import { + getSimMap, + receiverTypeMap, + SimAccel, + SimCANEncoder, + SimCANMotor, + SimPWM, + SimType, + supplierTypeMap, +} from "@/systems/simulation/wpilib_brain/WPILibBrain" +import World from "@/systems/World" +import { Random } from "@/util/Random" +import { XYPosition } from "@xyflow/react" +import WiringNode from "./WiringNode" +import { SimFlow, SimReceiver, SimSupplier } from "@/systems/simulation/wpilib_brain/SimDataFlow" +import { SimulationLayer } from "@/systems/simulation/SimulationSystem" + +export const NORA_TYPES_COLORS: { [k in NoraTypes]: string } = { + [NoraTypes.Number]: "#5f60ff", + [NoraTypes.Number2]: "#2bc275", + [NoraTypes.Number3]: "#ffc21a", + [NoraTypes.Unknown]: "#bebebe", +} + +let id = 0 +export function genId(): number { + return ++id +} + +export function genRandomId(): string { + return Math.floor(Random() * Number.MAX_SAFE_INTEGER).toString() +} + +const savedToGenMap = new Map() +const genToSavedMap = new Map() +function makeMapping(savedId: string): string { + const genId = (++id).toString() + savedToGenMap.set(savedId, genId) + genToSavedMap.set(genId, savedId) + return genId +} +export function savedIdToGenId(savedId: string): string { + const genId = savedToGenMap.get(savedId) + if (genId != undefined) { + return genId + } else { + return makeMapping(savedId) + } +} +export function genIdToSavedId(genId: string): string | undefined { + return genToSavedMap.get(genId) +} + +export const handleInfoDisplayCompare: (a: HandleInfo, b: HandleInfo) => number = (a, b) => + a.displayName.localeCompare(b.displayName) + +export const NODE_ID_ROBOT_IO = "robot-io-node" +export const NODE_ID_SIM_OUT = "sim-output-node" +export const NODE_ID_SIM_IN = "sim-input-node" + +export type ConfigState = "wiring" | "simIO" | "robotIO" +export type OriginType = SimType | StimulusType | DriverType +export enum FuncType { + Junction = "junct", + Constructor = "construct", + Deconstructor = "deconstruct", +} + +export type HandleInfo = { + id: string + nodeId: string + noraType: NoraTypes + originType?: OriginType + originId: string + + displayName: string + enabled: boolean + + many: boolean + isSource: boolean +} + +export type FlowControlsProps = { + onCreateJunction?: () => void +} + +export function getDriverSignals(assembly: MirabufSceneObject): Driver[] { + const simLayer = World.SimulationSystem.GetSimulationLayer(assembly.mechanism) + return simLayer?.drivers ?? [] +} + +export function getStimulusSignals(assembly: MirabufSceneObject): Stimulus[] { + const simLayer = World.SimulationSystem.GetSimulationLayer(assembly.mechanism) + return simLayer?.stimuli ?? [] +} + +export function getCANMotors(): [string, Map][] { + const cans = getSimMap()?.get(SimType.CANMotor) ?? new Map>() + return [...cans.entries()].filter(([_, data]) => data.get("][] { + return [...(getSimMap()?.get(SimType.CANEncoder)?.entries() ?? [])] +} + +export function getPWMDevices(): [string, Map][] { + const pwms = getSimMap()?.get(SimType.PWM) + if (pwms) { + return [...pwms.entries()].filter(([_, data]) => data.get("][] { + return [...(getSimMap()?.get(SimType.Accel)?.entries() ?? [])] +} + +export function getDIODevices(): [string, Map][] { + return [...(getSimMap()?.get(SimType.DIO)?.entries() ?? [])] +} + +function displayNameCAN(id: string) { + const a = id.indexOf("[") + const b = id.indexOf("]") + if (a === -1 || b === -1 || b - a < 2) return id + return `CAN [${id.substring(a + 1, b)}]` +} + +function displayNamePWM(id: string) { + return `PWM [${id}]` +} + +function displayNameAccel(id: string) { + if (id.startsWith("BuiltIn")) { + return "Accel [Built In]" + } else { + const a = id.indexOf("[") + const b = id.indexOf("]") + if (a === -1 || b === -1 || b - a < 2) return id + return `Accel [${id.substring(0, a)} - ${id.substring(a + 1, b)}]` + } +} + +// TODO +// function displayNameDI(id: string) { +// return `DI [${id}]` +// } + +// function displayNameDO(id: string) { +// return `DO [${id}]` +// } + +export type NodeInfo = { + id: string + type: string + funcType?: FuncType + position: XYPosition + tooltip?: string + sources: HandleId_Alias[] + targets: HandleId_Alias[] +} + +type NodeId_Alias = string +type HandleId_Alias = string +type EdgeId_Alias = string +type Edge_Alias = { sourceId: HandleId_Alias; targetId: HandleId_Alias } + +export type SimConfigData = { + handles: { [k: HandleId_Alias]: HandleInfo } + edges: { [k: EdgeId_Alias]: Edge_Alias } + adjacency: { [k: HandleId_Alias]: { [j: EdgeId_Alias]: boolean } } + nodes: { [k: NodeId_Alias]: NodeInfo } +} + +export class SimConfig { + private constructor() {} + + public static Default(assembly: MirabufSceneObject) { + const config: SimConfigData = { + handles: {}, + edges: {}, + adjacency: {}, + nodes: {}, + } + + SimConfig.AddRobotIONode(config) + const simInNode: NodeInfo = { + id: NODE_ID_SIM_IN, + type: WiringNode.name, + position: { x: 800, y: 0 }, + tooltip: + "These handles represent the input of the simulation. These are drivers for wheels, hinges, and sliders. Use the edit button to hide/reveal handles.", + sources: [], + targets: [], + } + const simOutNode: NodeInfo = { + id: NODE_ID_SIM_OUT, + type: WiringNode.name, + position: { x: -800, y: 0 }, + tooltip: + "These handles represent the output of the simulation. These are stimuli for wheels, hinges, and sliders that represent encoder positions and speeds. Use the edit button to hide/reveal handles.", + sources: [], + targets: [], + } + config.nodes[NODE_ID_SIM_IN] = simInNode + config.nodes[NODE_ID_SIM_OUT] = simOutNode + getDriverSignals(assembly).forEach(x => { + if (x.info?.GUID) { + const handle: HandleInfo = { + id: "", + nodeId: NODE_ID_SIM_IN, + noraType: x.getReceiverType(), + originType: x.id.type, + originId: x.idStr, + + displayName: x.DisplayName(), + enabled: true, + + many: hasNoraAverageFunc(x.getReceiverType()), + isSource: false, + } + this.AddHandle(config, handle) + simInNode.targets.push(handle.id) + } + }) + getStimulusSignals(assembly).forEach(x => { + if (x.info?.GUID) { + const handle: HandleInfo = { + id: "", + nodeId: NODE_ID_SIM_OUT, + noraType: x.getSupplierType(), + originType: x.id.type, + originId: x.idStr, + + displayName: x.DisplayName(), + enabled: true, + + many: hasNoraAverageFunc(x.getSupplierType()), + isSource: true, + } + this.AddHandle(config, handle) + simOutNode.sources.push(handle.id) + } else { + console.debug("Skipping stimulus", x) + } + }) + + return config + } + + public static RefreshRobotIO(config: SimConfigData) { + SimConfig.AddRobotIONode(config) + // TODO: Try to restore connections that remain valid after refresh + } + + private static AddRobotIONode(config: SimConfigData) { + if (config.nodes[NODE_ID_ROBOT_IO] != undefined) { + SimConfig.RemoveNode(config, NODE_ID_ROBOT_IO) + } + + const robotIONode: NodeInfo = { + id: NODE_ID_ROBOT_IO, + type: WiringNode.name, + position: { x: 0, y: 0 }, + tooltip: + "These handles represent the different devices we've discovered from your connected robot code. The left handles represent input devices such as sensors. The right handles represent output devices such as motor controllers. Use the edit button to hide/reveal handles.", + sources: [], + targets: [], + } + config.nodes[NODE_ID_ROBOT_IO] = robotIONode + getCANMotors().forEach(([id, _]) => { + const handle: HandleInfo = { + id: "", + nodeId: NODE_ID_ROBOT_IO, + noraType: supplierTypeMap[SimType.CANMotor]!, + originType: SimType.CANMotor, + originId: id, + + displayName: displayNameCAN(id), + enabled: true, + + many: true, + isSource: true, + } + this.AddHandle(config, handle) + robotIONode.sources.push(handle.id) + }) + getCANEncoder().forEach(([id, _]) => { + const handle: HandleInfo = { + id: "", + nodeId: NODE_ID_ROBOT_IO, + noraType: receiverTypeMap[SimType.CANEncoder]!, + originType: SimType.CANEncoder, + originId: id, + + displayName: displayNameCAN(id), + enabled: true, + + many: hasNoraAverageFunc(receiverTypeMap[SimType.CANEncoder]!), + isSource: false, + } + this.AddHandle(config, handle) + robotIONode.targets.push(handle.id) + }) + getPWMDevices().forEach(([id, _]) => { + const handle: HandleInfo = { + id: "", + nodeId: NODE_ID_ROBOT_IO, + noraType: supplierTypeMap[SimType.PWM]!, + originType: SimType.PWM, + originId: id, + + displayName: displayNamePWM(id), + enabled: true, + + many: true, + isSource: true, + } + this.AddHandle(config, handle) + robotIONode.sources.push(handle.id) + }) + getAccelDevices().forEach(([id, data]) => { + const handle: HandleInfo = { + id: "", + nodeId: NODE_ID_ROBOT_IO, + noraType: receiverTypeMap[SimType.Accel]!, + originType: SimType.Accel, + originId: id, + + displayName: displayNameAccel(id), + enabled: data.get(" { + // const handleIn: HandleInfo = { + // id: "", + // nodeId: NODE_ID_ROBOT_IO, + // noraType: receiverTypeMap[SimType.DIO]!, + // originType: SimType.DIO, + // originId: id, + + // displayName: displayNameDI(id), + // enabled: data.get(" this.DeleteEdge(config, x)) + delete config.adjacency[id] + delete config.handles[id] + return true + } + + public static RemoveNode(config: SimConfigData, id: NodeId_Alias): boolean { + if (config.nodes[id] == undefined) return false + ;[...Object.values(config.handles)].filter(x => x.nodeId == id).forEach(x => this.RemoveHandle(config, x.id)) + delete config.nodes[id] + return true + } + + public static AddJunctionNode(config: SimConfigData): NodeId_Alias { + let nodeId = "" + do { + nodeId = genRandomId() + } while (config.handles[nodeId] != undefined) + const node: NodeInfo = { + id: nodeId, + type: WiringNode.name, + position: { x: 300 + Random() * 100, y: -100 + Random() * 50 }, + funcType: FuncType.Junction, + targets: [], + sources: [], + } + config.nodes[nodeId] = node + + const targetHandle: HandleInfo = { + id: "", + nodeId: nodeId, + noraType: NoraTypes.Number, + originType: SimType.SimDevice, + originId: nodeId, + + displayName: "In", + enabled: true, + + many: true, + isSource: false, + } + SimConfig.AddHandle(config, targetHandle) + node.targets.push(targetHandle.id) + + const sourceHandle: HandleInfo = { + id: "", + nodeId: nodeId, + noraType: NoraTypes.Number, + originType: SimType.SimDevice, + originId: nodeId, + + displayName: "Out", + enabled: true, + + many: true, + isSource: true, + } + SimConfig.AddHandle(config, sourceHandle) + node.sources.push(sourceHandle.id) + return nodeId + } + + public static AddDeconstructorNode( + config: SimConfigData, + targetNoraType: NoraTypes, + positionHint?: XYPosition + ): HandleId_Alias | undefined { + const types = deconstructNoraType(targetNoraType) + if (types == undefined || types.length == 0) return undefined + + let nodeId = "" + do { + nodeId = genRandomId() + } while (config.handles[nodeId] != undefined) + const node: NodeInfo = { + id: nodeId, + type: WiringNode.name, + position: positionHint ?? { x: 0, y: 0 }, + funcType: FuncType.Deconstructor, + targets: [], + sources: [], + } + config.nodes[nodeId] = node + + const targetHandle: HandleInfo = { + id: "", + nodeId: nodeId, + noraType: targetNoraType, + originType: SimType.SimDevice, + originId: `target_${nodeId}`, + + displayName: "In", + enabled: true, + + many: hasNoraAverageFunc(targetNoraType), + isSource: false, + } + SimConfig.AddHandle(config, targetHandle) + node.targets.push(targetHandle.id) + + types.forEach((sourceType, i) => { + const sourceHandle: HandleInfo = { + id: "", + nodeId: nodeId, + noraType: sourceType, + originType: SimType.SimDevice, + originId: `source_${i}_${nodeId}`, + + displayName: `Out ${i + 1}`, + enabled: true, + + many: true, + isSource: true, + } + SimConfig.AddHandle(config, sourceHandle) + node.sources.push(sourceHandle.id) + }) + + return targetHandle.id + } + + public static AddConstructorNode( + config: SimConfigData, + sourceNoraType: NoraTypes, + positionHint?: XYPosition + ): HandleId_Alias | undefined { + const types = deconstructNoraType(sourceNoraType) + if (types == undefined || types.length == 0) return undefined + + let nodeId = "" + do { + nodeId = genRandomId() + } while (config.handles[nodeId] != undefined) + const node: NodeInfo = { + id: nodeId, + type: WiringNode.name, + position: positionHint ?? { x: 0, y: 0 }, + funcType: FuncType.Constructor, + targets: [], + sources: [], + } + config.nodes[nodeId] = node + + const sourceHandle: HandleInfo = { + id: "", + nodeId: nodeId, + noraType: sourceNoraType, + originType: SimType.SimDevice, + originId: `source_${nodeId}`, + + displayName: "Out", + enabled: true, + + many: true, + isSource: true, + } + SimConfig.AddHandle(config, sourceHandle) + node.sources.push(sourceHandle.id) + + types.forEach((targetType, i) => { + const targetHandle: HandleInfo = { + id: "", + nodeId: nodeId, + noraType: targetType, + originType: SimType.SimDevice, + originId: `target_${i}_${nodeId}`, + + displayName: `In ${i + 1}`, + enabled: true, + + many: hasNoraAverageFunc(targetType), + isSource: false, + } + SimConfig.AddHandle(config, targetHandle) + node.targets.push(targetHandle.id) + }) + + return sourceHandle.id + } + + public static GetEdge( + config: SimConfigData, + sourceId: HandleId_Alias, + targetId: HandleId_Alias + ): EdgeId_Alias | undefined { + const targetEdges = config.adjacency[targetId]! + return [...Object.keys(config.adjacency[sourceId]!)].filter(x => targetEdges[x] != undefined)[0] + } + + public static ValidateConnection( + config: SimConfigData, + sourceId: HandleId_Alias, + targetId: HandleId_Alias + ): boolean { + const sourceInfo = config.handles[sourceId] + const targetInfo = config.handles[targetId] + if (sourceInfo == undefined || targetInfo == undefined) return false + + if (!targetInfo.many && Object.entries(config.adjacency[targetId])!.length >= 1) return false + + return sourceInfo.noraType == targetInfo.noraType + } + + public static MakeConnection(config: SimConfigData, sourceId: HandleId_Alias, targetId: HandleId_Alias): boolean { + if (!SimConfig.ValidateConnection(config, sourceId, targetId)) { + console.error("Failed to make edge") + return false + } + + if (SimConfig.GetEdge(config, sourceId, targetId) != undefined) { + console.error("Connection already exists") + return false + } + + let edgeId = genRandomId() + while (config.edges[edgeId] != undefined) { + edgeId = genRandomId() + } + config.edges[edgeId] = { sourceId: sourceId, targetId: targetId } + config.adjacency[sourceId][edgeId] = true + config.adjacency[targetId][edgeId] = true + return true + } + + public static DeleteConnection(config: SimConfigData, sourceId: HandleId_Alias, targetId: HandleId_Alias): boolean { + const edgeId = SimConfig.GetEdge(config, sourceId, targetId) + if (edgeId == undefined) return false + delete config.adjacency[sourceId][edgeId] + delete config.adjacency[targetId][edgeId] + delete config.edges[edgeId] + return true + } + + public static DeleteEdge(config: SimConfigData, edgeId: EdgeId_Alias): boolean { + const edge = config.edges[edgeId] + if (edge == undefined) return false + delete config.adjacency[edge.sourceId][edgeId] + delete config.adjacency[edge.targetId][edgeId] + delete config.edges[edgeId] + return true + } + + public static Compile(config: SimConfigData, assembly: MirabufSceneObject): SimFlow[] | undefined { + const simLayer = World.SimulationSystem.GetSimulationLayer(assembly.mechanism) + if (!simLayer) { + console.error("No sim layer found") + return undefined + } + try { + const flows: SimFlow[] = [] + Object.entries(config.handles).forEach(([id, info]) => { + if ( + !info.isSource && + (info.nodeId == NODE_ID_ROBOT_IO || info.nodeId == NODE_ID_SIM_IN) && + (Object.entries(config.adjacency[info.id])?.length ?? 0) > 0 + ) { + const flow = SimConfig.CompileTargetHandle(config, simLayer, id, new Set()) + if (flow) flows.push(flow) + else throw new Error("Failed to compile flows") + } + }) + return flows + } catch (error) { + console.error("Error thrown during compilation", error) + return undefined + } + } + + public static CompileTargetHandle( + config: SimConfigData, + simLayer: SimulationLayer, + targetHandleId: HandleId_Alias, + encountered: Set + ): SimFlow | undefined { + const edges = Object.keys(config.adjacency[targetHandleId]) + if (!edges || edges.length < 1) { + console.warn("No edges found for target handle") + return undefined + } + + // Generate receiver + const targetHandle = config.handles[targetHandleId] + if (!targetHandle) return undefined + + const targetNoraType = targetHandle.noraType + let receiver: SimReceiver | undefined = undefined + if (targetHandle.nodeId == NODE_ID_ROBOT_IO) { + switch (targetHandle.originType) { + case SimType.CANEncoder: { + receiver = SimCANEncoder.GenReceiver(targetHandle.originId) + break + } + case SimType.Accel: { + receiver = SimAccel.GenReceiver(targetHandle.originId) + break + } + } + } else if (targetHandle.nodeId == NODE_ID_SIM_IN) { + receiver = simLayer.GetDriver(targetHandle.originId) + } else { + receiver = { + getReceiverType: () => targetHandle.noraType, + setReceiverValue: _ => { + console.debug("If you're seeing this, that means bad") + }, + } + } + if (!receiver) return undefined + + if (!hasNoraAverageFunc(targetNoraType) && edges.length > 1) return + + const suppliers: SimSupplier[] = [] + edges.forEach(edgeId => { + const edge = config.edges[edgeId] + if (!edge) return + const sourceHandle = config.handles[edge.sourceId] + if (!sourceHandle || sourceHandle.noraType != targetNoraType) return + if (encountered.has(sourceHandle.id)) return + encountered.add(sourceHandle.id) + switch (sourceHandle.nodeId) { + case NODE_ID_ROBOT_IO: { + // Get supplier from robot output + switch (sourceHandle.originType) { + case SimType.CANMotor: { + suppliers.push(SimCANMotor.GenSupplier(sourceHandle.originId)) + break + } + case SimType.PWM: { + suppliers.push(SimPWM.GenSupplier(sourceHandle.originId)) + break + } + } + break + } + case NODE_ID_SIM_OUT: { + // Get supplier from simulation output + const stim: SimSupplier | undefined = simLayer.GetStimuli(sourceHandle.originId) + if (stim) suppliers.push(stim) + break + } + default: { + // Figure out function type + const node = config.nodes[sourceHandle.nodeId] + if (!node?.funcType) break + const index = node.sources.indexOf(sourceHandle.id) + if (index == -1) break + const funcSuppliers = SimConfig.CompileFunctionNode(config, simLayer, node, encountered) + if (!funcSuppliers || funcSuppliers?.length != node.sources.length) break + suppliers.push(funcSuppliers[index]) + } + } + encountered.delete(sourceHandle.id) + }) + + if (suppliers.length == 0) return undefined + + if (suppliers.length == 1) { + return { + supplier: suppliers[0], + receiver: receiver, + } + } else { + const func = noraAverageFunc(targetNoraType) + if (!func) return undefined + return { + supplier: { + getSupplierType: () => targetNoraType, + getSupplierValue: func, + }, + receiver: receiver, + } + } + } + + public static CompileFunctionNode( + config: SimConfigData, + simLayer: SimulationLayer, + node: NodeInfo, + encountered: Set + ): SimSupplier[] | undefined { + switch (node.funcType) { + case FuncType.Constructor: { + if (node.sources.length != 1 || node.targets.length < 1) { + return undefined + } + const outputType = config.handles[node.sources[0]].noraType + const inputs = node.targets.map(x => { + const flow = SimConfig.CompileTargetHandle(config, simLayer, x, encountered) + if (!flow) { + console.error(`Failed to compile flow. TargetHandleId: ${x}`) + throw new Error("Failed to compile SimConfig") + } + return flow.supplier + }) + return [ + { + getSupplierType: () => outputType, + getSupplierValue: () => inputs.map(x => x.getSupplierValue()), + }, + ] + } + case FuncType.Deconstructor: { + if (node.sources.length < 1 || node.targets.length != 1) { + return undefined + } + const inputType = config.handles[node.targets[0]].noraType + const input = SimConfig.CompileTargetHandle(config, simLayer, node.targets[0], encountered) + if (!input) { + console.error(`Failed to compile flow. TargetHandleId: ${node.targets[0]}`) + throw new Error("Failed to compile SimConfig") + } + const deconstructedType = deconstructNoraType(inputType) + if (!deconstructedType) return undefined + const suppliers: SimSupplier[] = [] + for (let i = 0; i < deconstructedType.length; ++i) { + suppliers.push({ + getSupplierType: () => deconstructedType[i], + getSupplierValue: () => (input.supplier.getSupplierValue() as NoraType[])[i], + }) + } + return suppliers + } + case FuncType.Junction: { + if (node.sources.length != 1 || node.targets.length != 1) { + return undefined + } + const input = SimConfig.CompileTargetHandle(config, simLayer, node.targets[0], encountered) + if (!input) { + console.error(`Failed to compile flow. TargetHandleId: ${node.targets[0]}`) + throw new Error("Failed to compile SimConfig") + } + return [input.supplier] + break + } + } + return undefined + } +} diff --git a/fission/src/ui/panels/simulation/TextUpdaterNode.tsx b/fission/src/ui/panels/simulation/TextUpdaterNode.tsx new file mode 100644 index 0000000000..da8ad59ddc --- /dev/null +++ b/fission/src/ui/panels/simulation/TextUpdaterNode.tsx @@ -0,0 +1,30 @@ +import { useCallback, ChangeEvent } from "react" +import { Handle, NodeProps, Position } from "@xyflow/react" + +const handleStyle = { left: 10 } + +function TextUpdaterNode({ data, isConnectable }: NodeProps) { + const onChange = useCallback((evt: ChangeEvent) => { + console.log(evt.target.value) + }, []) + + return ( +
+ +
+ + +
+ + +
+ ) +} + +export default TextUpdaterNode diff --git a/fission/src/ui/panels/simulation/WiringNode.tsx b/fission/src/ui/panels/simulation/WiringNode.tsx new file mode 100644 index 0000000000..2718a0756b --- /dev/null +++ b/fission/src/ui/panels/simulation/WiringNode.tsx @@ -0,0 +1,126 @@ +import { Connection, Edge, Handle, NodeProps, Position } from "@xyflow/react" +import { handleInfoDisplayCompare, SimConfig, SimConfigData, HandleInfo, NORA_TYPES_COLORS } from "./SimConfigShared" +import { useCallback, useMemo } from "react" +import { CustomTooltip, DeleteButton, EditButton, RefreshButton } from "@/ui/components/StyledComponents" + +function WiringNode({ data, isConnectable }: NodeProps) { + const robotInput = data["input"] as HandleInfo[] | undefined + const robotOutput = data["output"] as HandleInfo[] | undefined + const onEdit = data["onEdit"] as (() => void) | undefined + const onRefresh = data["onRefresh"] as (() => void) | undefined + const onDelete = data["onDelete"] as (() => void) | undefined + const simConfig = data["simConfig"] as SimConfigData + const title = data["title"] as string + const tooltip = data["tooltip"] as string | undefined + + const validateConnection = useCallback( + (edge: Edge | Connection) => { + return SimConfig.ValidateConnection(simConfig, edge.sourceHandle!, edge.targetHandle!) + }, + [simConfig] + ) + + const inputHandles = useMemo( + () => + robotInput ? ( +
+ {robotInput.sort(handleInfoDisplayCompare).map((x, i) => { + return ( +
+
{x.displayName}
+ +
+ ) + })} +
+ ) : ( + <> + ), + [isConnectable, robotInput] + ) + + const outputHandles = useMemo( + () => + robotOutput ? ( +
+ {robotOutput.sort(handleInfoDisplayCompare).map((x, i) => { + return ( +
+
{x.displayName}
+ +
+ ) + })} +
+ ) : ( + <> + ), + [isConnectable, robotOutput, validateConnection] + ) + + return ( +
+
+ {tooltip ? CustomTooltip(tooltip) : <>} + {title} +
+
+ {inputHandles} + {outputHandles} +
+ {onEdit || onDelete ? ( +
+ {onEdit ? EditButton(onEdit) : <>} + {onRefresh ? RefreshButton(onRefresh) : <>} + {onDelete ? DeleteButton(onDelete) : <>} +
+ ) : ( + <> + )} +
+ ) +} + +export default WiringNode diff --git a/fission/src/ui/panels/simulation/WiringPanel.tsx b/fission/src/ui/panels/simulation/WiringPanel.tsx new file mode 100644 index 0000000000..37fa01fc6b --- /dev/null +++ b/fission/src/ui/panels/simulation/WiringPanel.tsx @@ -0,0 +1,488 @@ +import "@xyflow/react/dist/style.css" +import Panel, { PanelPropsImpl } from "@/components/Panel" +import { SectionDivider, SectionLabel, SynthesisIcons } from "@/ui/components/StyledComponents" +import React, { ComponentType, useCallback, useEffect, useMemo, useReducer, useState } from "react" +import { + ReactFlow, + Node as FlowNode, + Edge as FlowEdge, + useNodesState, + useEdgesState, + NodeProps, + Connection, + FinalConnectionState, + useReactFlow, + ReactFlowProvider, +} from "@xyflow/react" +import { + ConfigState, + HandleInfo, + handleInfoDisplayCompare, + NODE_ID_ROBOT_IO, + NODE_ID_SIM_IN, + NODE_ID_SIM_OUT, + SimConfig, +} from "./SimConfigShared" +import Label, { LabelSize } from "@/ui/components/Label" +import ScrollView from "@/ui/components/ScrollView" +import Checkbox from "@/ui/components/Checkbox" +import MirabufSceneObject from "@/mirabuf/MirabufSceneObject" +import World from "@/systems/World" +import Button from "@/ui/components/Button" +import { usePanelControlContext } from "@/ui/PanelContext" +import { Global_AddToast } from "@/ui/components/GlobalUIControls" +import { SimConfigData } from "./SimConfigShared" +import FlowControls from "./FlowControls" +import WiringNode from "./WiringNode" +import { SimType } from "@/systems/simulation/wpilib_brain/WPILibBrain" +import { isNoraDeconstructable } from "@/systems/simulation/Nora" +import InputSystem from "@/systems/input/InputSystem" +import FlowInfo from "./FlowInfo" + +type ConfigComponentProps = { + setConfigState: (state: ConfigState) => void + selectedAssembly: MirabufSceneObject + simConfig: SimConfigData + reset?: () => void +} + +type NodeType = ComponentType< + NodeProps & { + data: Record + type: string + } +> + +// This took way too long +const nodeTypes: Record = [WiringNode].reduce<{ [k: string]: NodeType }>((prev, next) => { + prev[next.name] = next + return prev +}, {}) + +function generateGraph( + simConfig: SimConfigData, + refreshGraph: () => void, + setConfigState: (state: ConfigState) => void +): [FlowNode[], FlowEdge[]] { + const nodes: Map = new Map() + const edges: FlowEdge[] = [] + + Object.entries(simConfig.nodes).forEach(([_k, v]) => { + let onEdit: (() => void) | undefined = undefined + let onRefresh: (() => void) | undefined = undefined + let onDelete: (() => void) | undefined = undefined + let title: string = "" + + switch (v.id) { + case NODE_ID_ROBOT_IO: + title = "Robot IO" + onEdit = () => setConfigState("robotIO") + onRefresh = () => { + SimConfig.RefreshRobotIO(simConfig) + refreshGraph() + } + break + case NODE_ID_SIM_IN: + title = "Simulation Input" + onEdit = () => setConfigState("simIO") + break + case NODE_ID_SIM_OUT: + title = "Simulation Output" + onEdit = () => setConfigState("simIO") + break + default: + onDelete = () => { + if (SimConfig.RemoveNode(simConfig, v.id)) refreshGraph() + } + break + } + + nodes.set(v.id, { + id: v.id, + type: v.type, + position: v.position, + data: { + title: title, + onEdit: onEdit, + onRefresh: onRefresh, + onDelete: onDelete, + simConfig: simConfig, + input: [], + output: [], + tooltip: v.tooltip, + }, + }) + }) + + Object.entries(simConfig.handles).forEach(([_k, v]) => { + if (!v.enabled) return + const node = nodes.get(v.nodeId) + if (!node) { + console.warn("Orphaned handle found") + return + } + const list = (v.isSource ? node.data.output : node.data.input) as unknown[] + list.push(v) + }) + + Object.entries(simConfig.edges).forEach(([k, v]) => { + const sourceHandle = simConfig.handles[v.sourceId] + const targetHandle = simConfig.handles[v.targetId] + + if (sourceHandle?.enabled && targetHandle?.enabled) { + edges.push({ + id: k, + source: sourceHandle.nodeId, + target: targetHandle.nodeId, + sourceHandle: sourceHandle.id, + targetHandle: targetHandle.id, + }) + } + }) + + return [[...nodes.values()], edges] +} + +function SimIOComponent({ setConfigState, simConfig }: ConfigComponentProps) { + const simOut: HandleInfo[] = [] + const simIn: HandleInfo[] = [] + Object.entries(simConfig.handles).forEach(([_k, v]) => { + if (v.nodeId == NODE_ID_SIM_OUT || v.nodeId == NODE_ID_SIM_IN) { + const list = v.isSource ? simOut : simIn + list.push(v) + } + }) + + return ( +
+ +
+
+ + + {simOut.sort(handleInfoDisplayCompare).map(handle => ( + { + handle.enabled = checked + }} + /> + ))} + +
+
+ + + {simIn.sort(handleInfoDisplayCompare).map(handle => ( + { + handle.enabled = checked + }} + /> + ))} + +
+
+
+ ) +} + +function RobotIOComponent({ setConfigState, simConfig }: ConfigComponentProps) { + const [canEncoders, canMotors, pwmDevices, accelerometers] = useMemo(() => { + const canEncoders: JSX.Element[] = [] + const canMotors: JSX.Element[] = [] + const pwmDevices: JSX.Element[] = [] + const accelerometers: JSX.Element[] = [] + + Object.entries(simConfig.handles).forEach(([_k, v]) => { + if (v.nodeId != NODE_ID_ROBOT_IO) return + + const checkbox = ( + { + v.enabled = checked + }} + /> + ) + + switch (v.originType) { + case SimType.CANMotor: + canMotors.push(checkbox) + break + case SimType.PWM: + pwmDevices.push(checkbox) + break + case SimType.CANEncoder: + canEncoders.push(checkbox) + break + case SimType.Accel: + accelerometers.push(checkbox) + break + } + }) + + return [canEncoders, canMotors, pwmDevices, accelerometers] + }, [simConfig]) + + return ( +
+ +
+
+ + + + CAN Encoders + + + {canEncoders} + + Accelerometers + + + {accelerometers} + +
+
+ + + + CAN Motors + + + {canMotors} + + PWM Devices + + + {pwmDevices} + +
+
+
+ ) +} + +function WiringComponent({ setConfigState, simConfig, reset }: ConfigComponentProps) { + const { screenToFlowPosition } = useReactFlow() + const [nodes, setNodes, onNodesChange] = useNodesState([] as FlowNode[]) + const [edges, setEdges, onEdgesChange] = useEdgesState([] as FlowEdge[]) + const [refreshHook, refreshGraph] = useReducer(x => !x, false) // Whenever I use reducers, it's always sketch. -Hunter + + // Essentially a callback, but it can use itself. + useEffect(() => { + const [nodes, edges] = generateGraph(simConfig, refreshGraph, setConfigState) + setNodes(nodes) + setEdges(edges) + }, [setConfigState, setEdges, setNodes, simConfig, refreshHook]) + + const onEdgeDoubleClick = useCallback( + (_: React.MouseEvent, edge: FlowEdge) => { + if (SimConfig.DeleteConnection(simConfig, edge.sourceHandle!, edge.targetHandle!)) { + refreshGraph() + } + }, + [simConfig] + ) + + const onNodeDragStop = useCallback( + (_event: React.MouseEvent, node: FlowNode, _nodes: FlowNode[]) => { + const nodeInfo = simConfig.nodes[node.id] + if (!nodeInfo) { + console.warn(`Unregistered Node detected: ${node.id}`) + return + } + nodeInfo.position = node.position + }, + [simConfig] + ) + + const onConnect = useCallback( + (connection: Connection) => { + const sourceId = connection.sourceHandle + const targetId = connection.targetHandle + if (SimConfig.MakeConnection(simConfig, sourceId!, targetId!)) { + refreshGraph() + } + }, + [simConfig] + ) + + const onConnectEnd = useCallback( + (event: MouseEvent | TouchEvent, state: FinalConnectionState) => { + if (state.isValid || state.fromHandle == null) return + + if (!(InputSystem.isKeyPressed("AltRight") || InputSystem.isKeyPressed("AltLeft"))) return + + const { clientX, clientY } = "changedTouches" in event ? event.changedTouches[0] : event + + const handleInfo = simConfig.handles[state.fromHandle.id!] + if (!handleInfo || !isNoraDeconstructable(handleInfo.noraType)) { + return + } + + const newHandleId = (handleInfo.isSource ? SimConfig.AddDeconstructorNode : SimConfig.AddConstructorNode)( + simConfig, + handleInfo.noraType, + screenToFlowPosition({ x: clientX, y: clientY }) + ) + if (!newHandleId) return + + if ( + handleInfo.isSource + ? SimConfig.MakeConnection(simConfig, handleInfo.id, newHandleId) + : SimConfig.MakeConnection(simConfig, newHandleId, handleInfo.id) + ) + refreshGraph() + }, + [screenToFlowPosition, simConfig] + ) + + const onCreateJunction = useCallback(() => { + SimConfig.AddJunctionNode(simConfig) + refreshGraph() + }, [refreshGraph, simConfig]) + + return ( + + {/* */} + + {})} /> + + ) +} + +function WiringPanel({ panelId }: PanelPropsImpl) { + const [configState, setConfigState] = useState("wiring") + const { closePanel } = usePanelControlContext() + const [simConfig, setSimConfig] = useState(undefined) + + const selectedAssembly = useMemo(() => { + const miraObjs = [...World.SceneRenderer.sceneObjects.entries()].filter(x => x[1] instanceof MirabufSceneObject) + if (miraObjs.length > 0) { + return miraObjs[0][1] as MirabufSceneObject + } else { + // TEMPORARY: Will be moved to config panel to ensure selected assembly + Global_AddToast?.("warning", "Missing Robot", "Must have at least one robot spawned for selection.") + closePanel(panelId) + } + }, [closePanel, panelId]) + + useEffect(() => { + if (!selectedAssembly) return + + const existingConfig = selectedAssembly.simConfigData + if (existingConfig) { + setSimConfig(JSON.parse(JSON.stringify(existingConfig))) // Create copy to not force a save + } else { + setSimConfig(SimConfig.Default(selectedAssembly)) + } + }, [selectedAssembly]) + + const save = useCallback(() => { + if (simConfig && selectedAssembly) { + const flows = SimConfig.Compile(simConfig, selectedAssembly) + if (!flows) { + console.error("Compilation Failed") + return + } + console.debug(`${flows.length} Flows Successfully Compiled!`) + + selectedAssembly.UpdateSimConfig(simConfig) + } + }, [selectedAssembly, simConfig]) + + const reset = useCallback(() => { + if (selectedAssembly) { + setSimConfig(SimConfig.Default(selectedAssembly)) + } + }, [selectedAssembly]) + + return ( + + {selectedAssembly && simConfig ? ( +
+ {configState === "wiring" ? ( + + + + ) : ( + <> + )} + {configState === "robotIO" ? ( + + ) : ( + <> + )} + {configState === "simIO" ? ( + + ) : ( + <> + )} +
+ ) : ( + <>ERRR + )} +
+ ) +} + +export default WiringPanel diff --git a/fission/src/util/Units.ts b/fission/src/util/Units.ts new file mode 100644 index 0000000000..425ac58f73 --- /dev/null +++ b/fission/src/util/Units.ts @@ -0,0 +1,73 @@ +import { getFontSize } from "./Utility" + +export class DOMUnitExpression { + public exprA: DOMUnitExpression | DOMUnit + public exprB?: DOMUnitExpression | DOMUnit + public op?: (a: number, b: number) => number + + private constructor( + exprA: DOMUnitExpression | DOMUnit, + exprB?: DOMUnitExpression | DOMUnit, + op?: (a: number, b: number) => number + ) { + this.exprA = exprA + this.exprB = exprB + this.op = op + } + + public static fromUnit(value: number, type?: DOMUnitTypes): DOMUnitExpression { + return new DOMUnitExpression(new DOMUnit(value, type ?? "px")) + } + + public evaluate(element: Element): number { + if (this.op && this.exprB) { + return this.op(this.exprA.evaluate(element), this.exprB.evaluate(element)) + } else { + return this.exprA.evaluate(element) + } + } + + public add(b: DOMUnit | DOMUnitExpression): DOMUnitExpression { + return new DOMUnitExpression(this, b, (x, y) => x + y) + } + + public sub(b: DOMUnit | DOMUnitExpression): DOMUnitExpression { + return new DOMUnitExpression(this, b, (x, y) => x - y) + } + + public mul(b: DOMUnit | DOMUnitExpression): DOMUnitExpression { + return new DOMUnitExpression(this, b, (x, y) => x * y) + } + + public div(b: DOMUnit | DOMUnitExpression): DOMUnitExpression { + return new DOMUnitExpression(this, b, (x, y) => x / y) + } +} + +type DOMUnitTypes = "px" | "rem" | "w" | "h" + +export class DOMUnit { + public type: DOMUnitTypes + public value: number + + public constructor(value: number, type: DOMUnitTypes) { + this.value = value + this.type = type + } + + public evaluate(element: Element, verbose: boolean = false): number { + if (verbose) console.debug(`${this.value} ${this.type} END UNIT`) + switch (this.type) { + case "px": + return this.value + case "rem": + return this.value * getFontSize(element) + case "w": + return this.value * element.clientWidth + case "h": + return this.value * element.clientHeight + default: + return 0 + } + } +} diff --git a/fission/src/util/Utility.ts b/fission/src/util/Utility.ts index f0e62c88d4..bf3c226863 100644 --- a/fission/src/util/Utility.ts +++ b/fission/src/util/Utility.ts @@ -1,3 +1,8 @@ export function ternaryOnce(obj: A | undefined, ifTrue: (x: A) => B, ifFalse: () => B): B { return obj ? ifTrue(obj) : ifFalse() } + +export function getFontSize(element: Element): number { + const str = window.getComputedStyle(element).fontSize + return Number(str.substring(0, str.length - 2)) +} diff --git a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/CANSparkMax.java b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/CANSparkMax.java index 8494d0b6f5..d696fabd26 100644 --- a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/CANSparkMax.java +++ b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/CANSparkMax.java @@ -37,7 +37,7 @@ public CANSparkMax(int deviceId, MotorType motorType) { * Sets the percent output of the real and simulated motors * Setting a follower doesn't break the simulated follower - leader relationship, which it does for exclusively non-simulated motors * - * @param percentOutput The new percent output of the motor + * @param percent The new percent output of the motor * * See the original documentation for more information */ @@ -85,6 +85,10 @@ public com.autodesk.synthesis.revrobotics.SparkAbsoluteEncoder getAbsoluteEncode return new SparkAbsoluteEncoder(super.getAbsoluteEncoder(), this.m_encoder); } + public com.autodesk.synthesis.revrobotics.RelativeEncoder getEncoderSim() { + return new RelativeEncoder(super.getEncoder(), this.m_encoder); + } + /** * Adds a follower to this motor controller. * diff --git a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/RelativeEncoder.java b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/RelativeEncoder.java new file mode 100644 index 0000000000..7046cd7df3 --- /dev/null +++ b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/RelativeEncoder.java @@ -0,0 +1,102 @@ +package com.autodesk.synthesis.revrobotics; + +import com.autodesk.synthesis.CANEncoder; +import com.revrobotics.REVLibError; + +public class RelativeEncoder implements com.revrobotics.RelativeEncoder { + + private com.revrobotics.RelativeEncoder m_original; + private CANEncoder m_encoder; + private double m_zero = 0.0; + private double m_positionConversionFactor = 1.0; + private double m_velocityConversionFactor = 1.0; + private double m_invertedFactor = 1.0; + + public RelativeEncoder(com.revrobotics.RelativeEncoder original, CANEncoder encoder) { + m_original = original; + m_encoder = encoder; + + m_positionConversionFactor = m_original.getPositionConversionFactor(); + m_velocityConversionFactor = m_original.getVelocityConversionFactor(); + m_invertedFactor = m_original.getInverted() ? -1.0 : 1.0; + } + + @Override + public double getPosition() { + return (m_encoder.getPosition() - m_zero) * m_positionConversionFactor * m_invertedFactor; + } + + @Override + public double getVelocity() { + return m_encoder.getVelocity() * m_velocityConversionFactor * m_invertedFactor; + } + + @Override + public REVLibError setPosition(double position) { + m_zero = position; + m_original.setPosition(position); + return REVLibError.kOk; + } + + @Override + public REVLibError setPositionConversionFactor(double factor) { + m_positionConversionFactor = factor; + m_original.setPositionConversionFactor(factor); + return REVLibError.kOk; + } + + @Override + public REVLibError setVelocityConversionFactor(double factor) { + m_velocityConversionFactor = factor; + m_original.setVelocityConversionFactor(factor); + return REVLibError.kOk; + } + + @Override + public double getPositionConversionFactor() { + return m_positionConversionFactor; + } + + @Override + public double getVelocityConversionFactor() { + return m_velocityConversionFactor; + } + + @Override + public REVLibError setAverageDepth(int depth) { + return m_original.setAverageDepth(depth); + } + + @Override + public int getAverageDepth() { + return m_original.getAverageDepth(); + } + + @Override + public REVLibError setMeasurementPeriod(int period_ms) { + return m_original.setMeasurementPeriod(period_ms); + } + + @Override + public int getMeasurementPeriod() { + return m_original.getMeasurementPeriod(); + } + + @Override + public int getCountsPerRevolution() { + return 1; + } + + @Override + public REVLibError setInverted(boolean inverted) { + m_invertedFactor = inverted ? -1.0 : 1.0; + m_original.setInverted(inverted); + return REVLibError.kOk; + } + + @Override + public boolean getInverted() { + return m_invertedFactor < 0.0; + } + +} diff --git a/simulation/samples/JavaAutoSample/.gitignore b/simulation/samples/JavaAutoSample/.gitignore new file mode 100644 index 0000000000..4a2a0df950 --- /dev/null +++ b/simulation/samples/JavaAutoSample/.gitignore @@ -0,0 +1,11 @@ +networktables.json +simgui-ds.json +simgui-window.json +simgui.json + +.gradle/ +.vscode/ +.wpilib/ +build/ +ctre_sim/ +bin/ diff --git a/simulation/samples/JavaAutoSample/WPILib-License.md b/simulation/samples/JavaAutoSample/WPILib-License.md new file mode 100644 index 0000000000..645e54253a --- /dev/null +++ b/simulation/samples/JavaAutoSample/WPILib-License.md @@ -0,0 +1,24 @@ +Copyright (c) 2009-2024 FIRST and other WPILib contributors +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of FIRST, WPILib, nor the names of other WPILib + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY FIRST AND OTHER WPILIB CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR +PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/simulation/samples/JavaAutoSample/build.gradle b/simulation/samples/JavaAutoSample/build.gradle new file mode 100644 index 0000000000..5acbea004b --- /dev/null +++ b/simulation/samples/JavaAutoSample/build.gradle @@ -0,0 +1,115 @@ +plugins { + id "java" + id "edu.wpi.first.GradleRIO" version "2024.3.2" +} + +repositories { + mavenLocal() +} + +// wpi.maven.useLocal = false +// wpi.maven.useFrcMavenLocalDevelopment = true +// wpi.versions.wpilibVersion = '2024.424242.+' +// wpi.versions.wpimathVersion = '2024.424242.+' + +java { + sourceCompatibility = JavaVersion.VERSION_17 + targetCompatibility = JavaVersion.VERSION_17 +} + +def ROBOT_MAIN_CLASS = "frc.robot.Main" + +// Define my targets (RoboRIO) and artifacts (deployable files) +// This is added by GradleRIO's backing project DeployUtils. +deploy { + targets { + roborio(getTargetTypeClass('RoboRIO')) { + // Team number is loaded either from the .wpilib/wpilib_preferences.json + // or from command line. If not found an exception will be thrown. + // You can use getTeamOrDefault(team) instead of getTeamNumber if you + // want to store a team number in this file. + team = project.frc.getTeamOrDefault(997) + debug = project.frc.getDebugOrDefault(false) + + artifacts { + // First part is artifact name, 2nd is artifact type + // getTargetTypeClass is a shortcut to get the class type using a string + + frcJava(getArtifactTypeClass('FRCJavaArtifact')) { + } + + // Static files artifact + frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { + files = project.fileTree('src/main/deploy') + directory = '/home/lvuser/deploy' + } + } + } + } +} + +def deployArtifact = deploy.targets.roborio.artifacts.frcJava + +// Set to true to use debug for JNI. +wpi.java.debugJni = false + +// Set this to true to enable desktop support. +def includeDesktopSupport = true + +// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. +// Also defines JUnit 5. +dependencies { + implementation wpi.java.deps.wpilib() + implementation wpi.java.vendor.java() + + roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) + roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) + + roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) + roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) + + nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) + nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) + simulationDebug wpi.sim.enableDebug() + + nativeRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.desktop) + nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) + simulationRelease wpi.sim.enableRelease() + + testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1' + testRuntimeOnly 'org.junit.platform:junit-platform-launcher' + + implementation "com.autodesk.synthesis:SyntheSimJava:1.0.0" +} + +test { + useJUnitPlatform() + systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' +} + +// Simulation configuration (e.g. environment variables). +wpi.sim.addGui().defaultEnabled = true +wpi.sim.addDriverstation() + +wpi.sim.envVar("HALSIMWS_HOST", "127.0.0.1") +wpi.sim.addWebsocketsServer().defaultEnabled = true + +// Setting up my Jar File. In this case, adding all libraries into the main jar ('fat jar') +// in order to make them all available at runtime. Also adding the manifest so WPILib +// knows where to look for our Robot Class. +jar { + from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } } + from sourceSets.main.allSource + manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) + duplicatesStrategy = DuplicatesStrategy.INCLUDE +} + +// Configure jar and deploy tasks +deployArtifact.jarTask = jar +wpi.java.configureExecutableTasks(jar) +wpi.java.configureTestTasks(test) + +// Configure string concat to always inline compile +tasks.withType(JavaCompile) { + options.compilerArgs.add '-XDstringConcat=inline' +} diff --git a/simulation/samples/JavaAutoSample/gradle/wrapper/gradle-wrapper.jar b/simulation/samples/JavaAutoSample/gradle/wrapper/gradle-wrapper.jar new file mode 100644 index 0000000000000000000000000000000000000000..d64cd4917707c1f8861d8cb53dd15194d4248596 GIT binary patch literal 43462 zcma&NWl&^owk(X(xVyW%ySuwf;qI=D6|RlDJ2cR^yEKh!@I- zp9QeisK*rlxC>+~7Dk4IxIRsKBHqdR9b3+fyL=ynHmIDe&|>O*VlvO+%z5;9Z$|DJ zb4dO}-R=MKr^6EKJiOrJdLnCJn>np?~vU-1sSFgPu;pthGwf}bG z(1db%xwr#x)r+`4AGu$j7~u2MpVs3VpLp|mx&;>`0p0vH6kF+D2CY0fVdQOZ@h;A` z{infNyvmFUiu*XG}RNMNwXrbec_*a3N=2zJ|Wh5z* z5rAX$JJR{#zP>KY**>xHTuw?|-Rg|o24V)74HcfVT;WtQHXlE+_4iPE8QE#DUm%x0 zEKr75ur~W%w#-My3Tj`hH6EuEW+8K-^5P62$7Sc5OK+22qj&Pd1;)1#4tKihi=~8C zHiQSst0cpri6%OeaR`PY>HH_;CPaRNty%WTm4{wDK8V6gCZlG@U3$~JQZ;HPvDJcT1V{ z?>H@13MJcCNe#5z+MecYNi@VT5|&UiN1D4ATT+%M+h4c$t;C#UAs3O_q=GxK0}8%8 z8J(_M9bayxN}69ex4dzM_P3oh@ZGREjVvn%%r7=xjkqxJP4kj}5tlf;QosR=%4L5y zWhgejO=vao5oX%mOHbhJ8V+SG&K5dABn6!WiKl{|oPkq(9z8l&Mm%(=qGcFzI=eLu zWc_oCLyf;hVlB@dnwY98?75B20=n$>u3b|NB28H0u-6Rpl((%KWEBOfElVWJx+5yg z#SGqwza7f}$z;n~g%4HDU{;V{gXIhft*q2=4zSezGK~nBgu9-Q*rZ#2f=Q}i2|qOp z!!y4p)4o=LVUNhlkp#JL{tfkhXNbB=Ox>M=n6soptJw-IDI|_$is2w}(XY>a=H52d z3zE$tjPUhWWS+5h=KVH&uqQS=$v3nRs&p$%11b%5qtF}S2#Pc`IiyBIF4%A!;AVoI zXU8-Rpv!DQNcF~(qQnyyMy=-AN~U>#&X1j5BLDP{?K!%h!;hfJI>$mdLSvktEr*89 zdJHvby^$xEX0^l9g$xW-d?J;L0#(`UT~zpL&*cEh$L|HPAu=P8`OQZV!-}l`noSp_ zQ-1$q$R-gDL)?6YaM!=8H=QGW$NT2SeZlb8PKJdc=F-cT@j7Xags+Pr*jPtlHFnf- zh?q<6;)27IdPc^Wdy-mX%2s84C1xZq9Xms+==F4);O`VUASmu3(RlgE#0+#giLh-& zcxm3_e}n4{%|X zJp{G_j+%`j_q5}k{eW&TlP}J2wtZ2^<^E(O)4OQX8FDp6RJq!F{(6eHWSD3=f~(h} zJXCf7=r<16X{pHkm%yzYI_=VDP&9bmI1*)YXZeB}F? z(%QsB5fo*FUZxK$oX~X^69;x~j7ms8xlzpt-T15e9}$4T-pC z6PFg@;B-j|Ywajpe4~bk#S6(fO^|mm1hKOPfA%8-_iGCfICE|=P_~e;Wz6my&)h_~ zkv&_xSAw7AZ%ThYF(4jADW4vg=oEdJGVOs>FqamoL3Np8>?!W#!R-0%2Bg4h?kz5I zKV-rKN2n(vUL%D<4oj@|`eJ>0i#TmYBtYmfla;c!ATW%;xGQ0*TW@PTlGG><@dxUI zg>+3SiGdZ%?5N=8uoLA|$4isK$aJ%i{hECP$bK{J#0W2gQ3YEa zZQ50Stn6hqdfxJ*9#NuSLwKFCUGk@c=(igyVL;;2^wi4o30YXSIb2g_ud$ zgpCr@H0qWtk2hK8Q|&wx)}4+hTYlf;$a4#oUM=V@Cw#!$(nOFFpZ;0lc!qd=c$S}Z zGGI-0jg~S~cgVT=4Vo)b)|4phjStD49*EqC)IPwyeKBLcN;Wu@Aeph;emROAwJ-0< z_#>wVm$)ygH|qyxZaet&(Vf%pVdnvKWJn9`%DAxj3ot;v>S$I}jJ$FLBF*~iZ!ZXE zkvui&p}fI0Y=IDX)mm0@tAd|fEHl~J&K}ZX(Mm3cm1UAuwJ42+AO5@HwYfDH7ipIc zmI;1J;J@+aCNG1M`Btf>YT>~c&3j~Qi@Py5JT6;zjx$cvOQW@3oQ>|}GH?TW-E z1R;q^QFjm5W~7f}c3Ww|awg1BAJ^slEV~Pk`Kd`PS$7;SqJZNj->it4DW2l15}xP6 zoCl$kyEF%yJni0(L!Z&14m!1urXh6Btj_5JYt1{#+H8w?5QI%% zo-$KYWNMJVH?Hh@1n7OSu~QhSswL8x0=$<8QG_zepi_`y_79=nK=_ZP_`Em2UI*tyQoB+r{1QYZCpb?2OrgUw#oRH$?^Tj!Req>XiE#~B|~ z+%HB;=ic+R@px4Ld8mwpY;W^A%8%l8$@B@1m5n`TlKI6bz2mp*^^^1mK$COW$HOfp zUGTz-cN9?BGEp}5A!mDFjaiWa2_J2Iq8qj0mXzk; z66JBKRP{p%wN7XobR0YjhAuW9T1Gw3FDvR5dWJ8ElNYF94eF3ebu+QwKjtvVu4L zI9ip#mQ@4uqVdkl-TUQMb^XBJVLW(-$s;Nq;@5gr4`UfLgF$adIhd?rHOa%D);whv z=;krPp~@I+-Z|r#s3yCH+c1US?dnm+C*)r{m+86sTJusLdNu^sqLrfWed^ndHXH`m zd3#cOe3>w-ga(Dus_^ppG9AC>Iq{y%%CK+Cro_sqLCs{VLuK=dev>OL1dis4(PQ5R zcz)>DjEkfV+MO;~>VUlYF00SgfUo~@(&9$Iy2|G0T9BSP?&T22>K46D zL*~j#yJ?)^*%J3!16f)@Y2Z^kS*BzwfAQ7K96rFRIh>#$*$_Io;z>ux@}G98!fWR@ zGTFxv4r~v)Gsd|pF91*-eaZ3Qw1MH$K^7JhWIdX%o$2kCbvGDXy)a?@8T&1dY4`;L z4Kn+f%SSFWE_rpEpL9bnlmYq`D!6F%di<&Hh=+!VI~j)2mfil03T#jJ_s?}VV0_hp z7T9bWxc>Jm2Z0WMU?`Z$xE74Gu~%s{mW!d4uvKCx@WD+gPUQ zV0vQS(Ig++z=EHN)BR44*EDSWIyT~R4$FcF*VEY*8@l=218Q05D2$|fXKFhRgBIEE zdDFB}1dKkoO^7}{5crKX!p?dZWNz$m>1icsXG2N+((x0OIST9Zo^DW_tytvlwXGpn zs8?pJXjEG;T@qrZi%#h93?FP$!&P4JA(&H61tqQi=opRzNpm zkrG}$^t9&XduK*Qa1?355wd8G2CI6QEh@Ua>AsD;7oRUNLPb76m4HG3K?)wF~IyS3`fXuNM>${?wmB zpVz;?6_(Fiadfd{vUCBM*_kt$+F3J+IojI;9L(gc9n3{sEZyzR9o!_mOwFC#tQ{Q~ zP3-`#uK#tP3Q7~Q;4H|wjZHO8h7e4IuBxl&vz2w~D8)w=Wtg31zpZhz%+kzSzL*dV zwp@{WU4i;hJ7c2f1O;7Mz6qRKeASoIv0_bV=i@NMG*l<#+;INk-^`5w@}Dj~;k=|}qM1vq_P z|GpBGe_IKq|LNy9SJhKOQ$c=5L{Dv|Q_lZl=-ky*BFBJLW9&y_C|!vyM~rQx=!vun z?rZJQB5t}Dctmui5i31C_;_}CEn}_W%>oSXtt>@kE1=JW*4*v4tPp;O6 zmAk{)m!)}34pTWg8{i>($%NQ(Tl;QC@J@FfBoc%Gr&m560^kgSfodAFrIjF}aIw)X zoXZ`@IsMkc8_=w%-7`D6Y4e*CG8k%Ud=GXhsTR50jUnm+R*0A(O3UKFg0`K;qp1bl z7``HN=?39ic_kR|^R^~w-*pa?Vj#7|e9F1iRx{GN2?wK!xR1GW!qa=~pjJb-#u1K8 zeR?Y2i-pt}yJq;SCiVHODIvQJX|ZJaT8nO+(?HXbLefulKKgM^B(UIO1r+S=7;kLJ zcH}1J=Px2jsh3Tec&v8Jcbng8;V-`#*UHt?hB(pmOipKwf3Lz8rG$heEB30Sg*2rx zV<|KN86$soN(I!BwO`1n^^uF2*x&vJ$2d$>+`(romzHP|)K_KkO6Hc>_dwMW-M(#S zK(~SiXT1@fvc#U+?|?PniDRm01)f^#55;nhM|wi?oG>yBsa?~?^xTU|fX-R(sTA+5 zaq}-8Tx7zrOy#3*JLIIVsBmHYLdD}!0NP!+ITW+Thn0)8SS!$@)HXwB3tY!fMxc#1 zMp3H?q3eD?u&Njx4;KQ5G>32+GRp1Ee5qMO0lZjaRRu&{W<&~DoJNGkcYF<5(Ab+J zgO>VhBl{okDPn78<%&e2mR{jwVCz5Og;*Z;;3%VvoGo_;HaGLWYF7q#jDX=Z#Ml`H z858YVV$%J|e<1n`%6Vsvq7GmnAV0wW4$5qQ3uR@1i>tW{xrl|ExywIc?fNgYlA?C5 zh$ezAFb5{rQu6i7BSS5*J-|9DQ{6^BVQ{b*lq`xS@RyrsJN?-t=MTMPY;WYeKBCNg z^2|pN!Q^WPJuuO4!|P@jzt&tY1Y8d%FNK5xK(!@`jO2aEA*4 zkO6b|UVBipci?){-Ke=+1;mGlND8)6+P;8sq}UXw2hn;fc7nM>g}GSMWu&v&fqh

iViYT=fZ(|3Ox^$aWPp4a8h24tD<|8-!aK0lHgL$N7Efw}J zVIB!7=T$U`ao1?upi5V4Et*-lTG0XvExbf!ya{cua==$WJyVG(CmA6Of*8E@DSE%L z`V^$qz&RU$7G5mg;8;=#`@rRG`-uS18$0WPN@!v2d{H2sOqP|!(cQ@ zUHo!d>>yFArLPf1q`uBvY32miqShLT1B@gDL4XoVTK&@owOoD)OIHXrYK-a1d$B{v zF^}8D3Y^g%^cnvScOSJR5QNH+BI%d|;J;wWM3~l>${fb8DNPg)wrf|GBP8p%LNGN# z3EaIiItgwtGgT&iYCFy9-LG}bMI|4LdmmJt@V@% zb6B)1kc=T)(|L@0;wr<>=?r04N;E&ef+7C^`wPWtyQe(*pD1pI_&XHy|0gIGHMekd zF_*M4yi6J&Z4LQj65)S zXwdM{SwUo%3SbPwFsHgqF@V|6afT|R6?&S;lw=8% z3}@9B=#JI3@B*#4s!O))~z zc>2_4Q_#&+5V`GFd?88^;c1i7;Vv_I*qt!_Yx*n=;rj!82rrR2rQ8u5(Ejlo{15P% zs~!{%XJ>FmJ})H^I9bn^Re&38H{xA!0l3^89k(oU;bZWXM@kn$#aoS&Y4l^-WEn-fH39Jb9lA%s*WsKJQl?n9B7_~P z-XM&WL7Z!PcoF6_D>V@$CvUIEy=+Z&0kt{szMk=f1|M+r*a43^$$B^MidrT0J;RI` z(?f!O<8UZkm$_Ny$Hth1J#^4ni+im8M9mr&k|3cIgwvjAgjH z8`N&h25xV#v*d$qBX5jkI|xOhQn!>IYZK7l5#^P4M&twe9&Ey@@GxYMxBZq2e7?`q z$~Szs0!g{2fGcp9PZEt|rdQ6bhAgpcLHPz?f-vB?$dc*!9OL?Q8mn7->bFD2Si60* z!O%y)fCdMSV|lkF9w%x~J*A&srMyYY3{=&$}H zGQ4VG_?$2X(0|vT0{=;W$~icCI{b6W{B!Q8xdGhF|D{25G_5_+%s(46lhvNLkik~R z>nr(&C#5wwOzJZQo9m|U<;&Wk!_#q|V>fsmj1g<6%hB{jGoNUPjgJslld>xmODzGjYc?7JSuA?A_QzjDw5AsRgi@Y|Z0{F{!1=!NES-#*f^s4l0Hu zz468))2IY5dmD9pa*(yT5{EyP^G>@ZWumealS-*WeRcZ}B%gxq{MiJ|RyX-^C1V=0 z@iKdrGi1jTe8Ya^x7yyH$kBNvM4R~`fbPq$BzHum-3Zo8C6=KW@||>zsA8-Y9uV5V z#oq-f5L5}V<&wF4@X@<3^C%ptp6+Ce)~hGl`kwj)bsAjmo_GU^r940Z-|`<)oGnh7 zFF0Tde3>ui?8Yj{sF-Z@)yQd~CGZ*w-6p2U<8}JO-sRsVI5dBji`01W8A&3$?}lxBaC&vn0E$c5tW* zX>5(zzZ=qn&!J~KdsPl;P@bmA-Pr8T*)eh_+Dv5=Ma|XSle6t(k8qcgNyar{*ReQ8 zTXwi=8vr>!3Ywr+BhggHDw8ke==NTQVMCK`$69fhzEFB*4+H9LIvdt-#IbhZvpS}} zO3lz;P?zr0*0$%-Rq_y^k(?I{Mk}h@w}cZpMUp|ucs55bcloL2)($u%mXQw({Wzc~ z;6nu5MkjP)0C(@%6Q_I_vsWrfhl7Zpoxw#WoE~r&GOSCz;_ro6i(^hM>I$8y>`!wW z*U^@?B!MMmb89I}2(hcE4zN2G^kwyWCZp5JG>$Ez7zP~D=J^LMjSM)27_0B_X^C(M z`fFT+%DcKlu?^)FCK>QzSnV%IsXVcUFhFdBP!6~se&xxrIxsvySAWu++IrH;FbcY$ z2DWTvSBRfLwdhr0nMx+URA$j3i7_*6BWv#DXfym?ZRDcX9C?cY9sD3q)uBDR3uWg= z(lUIzB)G$Hr!){>E{s4Dew+tb9kvToZp-1&c?y2wn@Z~(VBhqz`cB;{E4(P3N2*nJ z_>~g@;UF2iG{Kt(<1PyePTKahF8<)pozZ*xH~U-kfoAayCwJViIrnqwqO}7{0pHw$ zs2Kx?s#vQr7XZ264>5RNKSL8|Ty^=PsIx^}QqOOcfpGUU4tRkUc|kc7-!Ae6!+B{o~7nFpm3|G5^=0#Bnm6`V}oSQlrX(u%OWnC zoLPy&Q;1Jui&7ST0~#+}I^&?vcE*t47~Xq#YwvA^6^} z`WkC)$AkNub|t@S!$8CBlwbV~?yp&@9h{D|3z-vJXgzRC5^nYm+PyPcgRzAnEi6Q^gslXYRv4nycsy-SJu?lMps-? zV`U*#WnFsdPLL)Q$AmD|0`UaC4ND07+&UmOu!eHruzV|OUox<+Jl|Mr@6~C`T@P%s zW7sgXLF2SSe9Fl^O(I*{9wsFSYb2l%-;&Pi^dpv!{)C3d0AlNY6!4fgmSgj_wQ*7Am7&$z;Jg&wgR-Ih;lUvWS|KTSg!&s_E9_bXBkZvGiC6bFKDWZxsD$*NZ#_8bl zG1P-#@?OQzED7@jlMJTH@V!6k;W>auvft)}g zhoV{7$q=*;=l{O>Q4a@ ziMjf_u*o^PsO)#BjC%0^h>Xp@;5$p{JSYDt)zbb}s{Kbt!T*I@Pk@X0zds6wsefuU zW$XY%yyRGC94=6mf?x+bbA5CDQ2AgW1T-jVAJbm7K(gp+;v6E0WI#kuACgV$r}6L? zd|Tj?^%^*N&b>Dd{Wr$FS2qI#Ucs1yd4N+RBUQiSZGujH`#I)mG&VKoDh=KKFl4=G z&MagXl6*<)$6P}*Tiebpz5L=oMaPrN+caUXRJ`D?=K9!e0f{@D&cZLKN?iNP@X0aF zE(^pl+;*T5qt?1jRC=5PMgV!XNITRLS_=9{CJExaQj;lt!&pdzpK?8p>%Mb+D z?yO*uSung=-`QQ@yX@Hyd4@CI^r{2oiu`%^bNkz+Nkk!IunjwNC|WcqvX~k=><-I3 zDQdbdb|!v+Iz01$w@aMl!R)koD77Xp;eZwzSl-AT zr@Vu{=xvgfq9akRrrM)}=!=xcs+U1JO}{t(avgz`6RqiiX<|hGG1pmop8k6Q+G_mv zJv|RfDheUp2L3=^C=4aCBMBn0aRCU(DQwX-W(RkRwmLeuJYF<0urcaf(=7)JPg<3P zQs!~G)9CT18o!J4{zX{_e}4eS)U-E)0FAt}wEI(c0%HkxgggW;(1E=>J17_hsH^sP z%lT0LGgbUXHx-K*CI-MCrP66UP0PvGqM$MkeLyqHdbgP|_Cm!7te~b8p+e6sQ_3k| zVcwTh6d83ltdnR>D^)BYQpDKlLk3g0Hdcgz2}%qUs9~~Rie)A-BV1mS&naYai#xcZ z(d{8=-LVpTp}2*y)|gR~;qc7fp26}lPcLZ#=JpYcn3AT9(UIdOyg+d(P5T7D&*P}# zQCYplZO5|7+r19%9e`v^vfSS1sbX1c%=w1;oyruXB%Kl$ACgKQ6=qNWLsc=28xJjg zwvsI5-%SGU|3p>&zXVl^vVtQT3o-#$UT9LI@Npz~6=4!>mc431VRNN8od&Ul^+G_kHC`G=6WVWM z%9eWNyy(FTO|A+@x}Ou3CH)oi;t#7rAxdIXfNFwOj_@Y&TGz6P_sqiB`Q6Lxy|Q{`|fgmRG(k+!#b*M+Z9zFce)f-7;?Km5O=LHV9f9_87; zF7%R2B+$?@sH&&-$@tzaPYkw0;=i|;vWdI|Wl3q_Zu>l;XdIw2FjV=;Mq5t1Q0|f< zs08j54Bp`3RzqE=2enlkZxmX6OF+@|2<)A^RNQpBd6o@OXl+i)zO%D4iGiQNuXd+zIR{_lb96{lc~bxsBveIw6umhShTX+3@ZJ=YHh@ zWY3(d0azg;7oHn>H<>?4@*RQbi>SmM=JrHvIG(~BrvI)#W(EAeO6fS+}mxxcc+X~W6&YVl86W9WFSS}Vz-f9vS?XUDBk)3TcF z8V?$4Q)`uKFq>xT=)Y9mMFVTUk*NIA!0$?RP6Ig0TBmUFrq*Q-Agq~DzxjStQyJ({ zBeZ;o5qUUKg=4Hypm|}>>L=XKsZ!F$yNTDO)jt4H0gdQ5$f|d&bnVCMMXhNh)~mN z@_UV6D7MVlsWz+zM+inZZp&P4fj=tm6fX)SG5H>OsQf_I8c~uGCig$GzuwViK54bcgL;VN|FnyQl>Ed7(@>=8$a_UKIz|V6CeVSd2(P z0Uu>A8A+muM%HLFJQ9UZ5c)BSAv_zH#1f02x?h9C}@pN@6{>UiAp>({Fn(T9Q8B z^`zB;kJ5b`>%dLm+Ol}ty!3;8f1XDSVX0AUe5P#@I+FQ-`$(a;zNgz)4x5hz$Hfbg z!Q(z26wHLXko(1`;(BAOg_wShpX0ixfWq3ponndY+u%1gyX)_h=v1zR#V}#q{au6; z!3K=7fQwnRfg6FXtNQmP>`<;!N137paFS%y?;lb1@BEdbvQHYC{976l`cLqn;b8lp zIDY>~m{gDj(wfnK!lpW6pli)HyLEiUrNc%eXTil|F2s(AY+LW5hkKb>TQ3|Q4S9rr zpDs4uK_co6XPsn_z$LeS{K4jFF`2>U`tbgKdyDne`xmR<@6AA+_hPNKCOR-Zqv;xk zu5!HsBUb^!4uJ7v0RuH-7?l?}b=w5lzzXJ~gZcxRKOovSk@|#V+MuX%Y+=;14i*%{)_gSW9(#4%)AV#3__kac1|qUy!uyP{>?U#5wYNq}y$S9pCc zFc~4mgSC*G~j0u#qqp9 z${>3HV~@->GqEhr_Xwoxq?Hjn#=s2;i~g^&Hn|aDKpA>Oc%HlW(KA1?BXqpxB;Ydx)w;2z^MpjJ(Qi(X!$5RC z*P{~%JGDQqojV>2JbEeCE*OEu!$XJ>bWA9Oa_Hd;y)F%MhBRi*LPcdqR8X`NQ&1L# z5#9L*@qxrx8n}LfeB^J{%-?SU{FCwiWyHp682F+|pa+CQa3ZLzBqN1{)h4d6+vBbV zC#NEbQLC;}me3eeYnOG*nXOJZEU$xLZ1<1Y=7r0(-U0P6-AqwMAM`a(Ed#7vJkn6plb4eI4?2y3yOTGmmDQ!z9`wzbf z_OY#0@5=bnep;MV0X_;;SJJWEf^E6Bd^tVJ9znWx&Ks8t*B>AM@?;D4oWUGc z!H*`6d7Cxo6VuyS4Eye&L1ZRhrRmN6Lr`{NL(wDbif|y&z)JN>Fl5#Wi&mMIr5i;x zBx}3YfF>>8EC(fYnmpu~)CYHuHCyr5*`ECap%t@y=jD>!_%3iiE|LN$mK9>- zHdtpy8fGZtkZF?%TW~29JIAfi2jZT8>OA7=h;8T{{k?c2`nCEx9$r zS+*&vt~2o^^J+}RDG@+9&M^K*z4p{5#IEVbz`1%`m5c2};aGt=V?~vIM}ZdPECDI)47|CWBCfDWUbxBCnmYivQ*0Nu_xb*C>~C9(VjHM zxe<*D<#dQ8TlpMX2c@M<9$w!RP$hpG4cs%AI){jp*Sj|*`m)5(Bw*A0$*i-(CA5#%>a)$+jI2C9r6|(>J8InryENI z$NohnxDUB;wAYDwrb*!N3noBTKPpPN}~09SEL18tkG zxgz(RYU_;DPT{l?Q$+eaZaxnsWCA^ds^0PVRkIM%bOd|G2IEBBiz{&^JtNsODs;5z zICt_Zj8wo^KT$7Bg4H+y!Df#3mbl%%?|EXe!&(Vmac1DJ*y~3+kRKAD=Ovde4^^%~ zw<9av18HLyrf*_>Slp;^i`Uy~`mvBjZ|?Ad63yQa#YK`4+c6;pW4?XIY9G1(Xh9WO8{F-Aju+nS9Vmv=$Ac0ienZ+p9*O%NG zMZKy5?%Z6TAJTE?o5vEr0r>f>hb#2w2U3DL64*au_@P!J!TL`oH2r*{>ffu6|A7tv zL4juf$DZ1MW5ZPsG!5)`k8d8c$J$o;%EIL0va9&GzWvkS%ZsGb#S(?{!UFOZ9<$a| zY|a+5kmD5N&{vRqkgY>aHsBT&`rg|&kezoD)gP0fsNYHsO#TRc_$n6Lf1Z{?+DLziXlHrq4sf(!>O{?Tj;Eh@%)+nRE_2VxbN&&%%caU#JDU%vL3}Cb zsb4AazPI{>8H&d=jUaZDS$-0^AxE@utGs;-Ez_F(qC9T=UZX=>ok2k2 ziTn{K?y~a5reD2A)P${NoI^>JXn>`IeArow(41c-Wm~)wiryEP(OS{YXWi7;%dG9v zI?mwu1MxD{yp_rrk!j^cKM)dc4@p4Ezyo%lRN|XyD}}>v=Xoib0gOcdXrQ^*61HNj z=NP|pd>@yfvr-=m{8$3A8TQGMTE7g=z!%yt`8`Bk-0MMwW~h^++;qyUP!J~ykh1GO z(FZ59xuFR$(WE;F@UUyE@Sp>`aVNjyj=Ty>_Vo}xf`e7`F;j-IgL5`1~-#70$9_=uBMq!2&1l zomRgpD58@)YYfvLtPW}{C5B35R;ZVvB<<#)x%srmc_S=A7F@DW8>QOEGwD6suhwCg z>Pa+YyULhmw%BA*4yjDp|2{!T98~<6Yfd(wo1mQ!KWwq0eg+6)o1>W~f~kL<-S+P@$wx*zeI|1t7z#Sxr5 zt6w+;YblPQNplq4Z#T$GLX#j6yldXAqj>4gAnnWtBICUnA&-dtnlh=t0Ho_vEKwV` z)DlJi#!@nkYV#$!)@>udAU*hF?V`2$Hf=V&6PP_|r#Iv*J$9)pF@X3`k;5})9^o4y z&)~?EjX5yX12O(BsFy-l6}nYeuKkiq`u9145&3Ssg^y{5G3Pse z9w(YVa0)N-fLaBq1`P!_#>SS(8fh_5!f{UrgZ~uEdeMJIz7DzI5!NHHqQtm~#CPij z?=N|J>nPR6_sL7!f4hD_|KH`vf8(Wpnj-(gPWH+ZvID}%?~68SwhPTC3u1_cB`otq z)U?6qo!ZLi5b>*KnYHWW=3F!p%h1;h{L&(Q&{qY6)_qxNfbP6E3yYpW!EO+IW3?@J z);4>g4gnl^8klu7uA>eGF6rIGSynacogr)KUwE_R4E5Xzi*Qir@b-jy55-JPC8c~( zo!W8y9OGZ&`xmc8;=4-U9=h{vCqfCNzYirONmGbRQlR`WWlgnY+1wCXbMz&NT~9*| z6@FrzP!LX&{no2!Ln_3|I==_4`@}V?4a;YZKTdw;vT<+K+z=uWbW(&bXEaWJ^W8Td z-3&1bY^Z*oM<=M}LVt>_j+p=2Iu7pZmbXrhQ_k)ysE9yXKygFNw$5hwDn(M>H+e1&9BM5!|81vd%r%vEm zqxY3?F@fb6O#5UunwgAHR9jp_W2zZ}NGp2%mTW@(hz7$^+a`A?mb8|_G*GNMJ) zjqegXQio=i@AINre&%ofexAr95aop5C+0MZ0m-l=MeO8m3epm7U%vZB8+I+C*iNFM z#T3l`gknX;D$-`2XT^Cg*vrv=RH+P;_dfF++cP?B_msQI4j+lt&rX2)3GaJx%W*Nn zkML%D{z5tpHH=dksQ*gzc|}gzW;lwAbxoR07VNgS*-c3d&8J|;@3t^ zVUz*J*&r7DFRuFVDCJDK8V9NN5hvpgGjwx+5n)qa;YCKe8TKtdnh{I7NU9BCN!0dq zczrBk8pE{{@vJa9ywR@mq*J=v+PG;?fwqlJVhijG!3VmIKs>9T6r7MJpC)m!Tc#>g zMtVsU>wbwFJEfwZ{vB|ZlttNe83)$iz`~#8UJ^r)lJ@HA&G#}W&ZH*;k{=TavpjWE z7hdyLZPf*X%Gm}i`Y{OGeeu^~nB8=`{r#TUrM-`;1cBvEd#d!kPqIgYySYhN-*1;L z^byj%Yi}Gx)Wnkosi337BKs}+5H5dth1JA{Ir-JKN$7zC)*}hqeoD(WfaUDPT>0`- z(6sa0AoIqASwF`>hP}^|)a_j2s^PQn*qVC{Q}htR z5-)duBFXT_V56-+UohKXlq~^6uf!6sA#ttk1o~*QEy_Y-S$gAvq47J9Vtk$5oA$Ct zYhYJ@8{hsC^98${!#Ho?4y5MCa7iGnfz}b9jE~h%EAAv~Qxu)_rAV;^cygV~5r_~?l=B`zObj7S=H=~$W zPtI_m%g$`kL_fVUk9J@>EiBH zOO&jtn~&`hIFMS5S`g8w94R4H40mdNUH4W@@XQk1sr17b{@y|JB*G9z1|CrQjd+GX z6+KyURG3;!*BQrentw{B2R&@2&`2}n(z-2&X7#r!{yg@Soy}cRD~j zj9@UBW+N|4HW4AWapy4wfUI- zZ`gSL6DUlgj*f1hSOGXG0IVH8HxK?o2|3HZ;KW{K+yPAlxtb)NV_2AwJm|E)FRs&& z=c^e7bvUsztY|+f^k7NXs$o1EUq>cR7C0$UKi6IooHWlK_#?IWDkvywnzg&ThWo^? z2O_N{5X39#?eV9l)xI(>@!vSB{DLt*oY!K1R8}_?%+0^C{d9a%N4 zoxHVT1&Lm|uDX%$QrBun5e-F`HJ^T$ zmzv)p@4ZHd_w9!%Hf9UYNvGCw2TTTbrj9pl+T9%-_-}L(tES>Or-}Z4F*{##n3~L~TuxjirGuIY#H7{%$E${?p{Q01 zi6T`n;rbK1yIB9jmQNycD~yZq&mbIsFWHo|ZAChSFPQa<(%d8mGw*V3fh|yFoxOOiWJd(qvVb!Z$b88cg->N=qO*4k~6;R==|9ihg&riu#P~s4Oap9O7f%crSr^rljeIfXDEg>wi)&v*a%7zpz<9w z*r!3q9J|390x`Zk;g$&OeN&ctp)VKRpDSV@kU2Q>jtok($Y-*x8_$2piTxun81@vt z!Vj?COa0fg2RPXMSIo26T=~0d`{oGP*eV+$!0I<(4azk&Vj3SiG=Q!6mX0p$z7I}; z9BJUFgT-K9MQQ-0@Z=^7R<{bn2Fm48endsSs`V7_@%8?Bxkqv>BDoVcj?K#dV#uUP zL1ND~?D-|VGKe3Rw_7-Idpht>H6XRLh*U7epS6byiGvJpr%d}XwfusjH9g;Z98H`x zyde%%5mhGOiL4wljCaWCk-&uE4_OOccb9c!ZaWt4B(wYl!?vyzl%7n~QepN&eFUrw zFIOl9c({``6~QD+43*_tzP{f2x41h(?b43^y6=iwyB)2os5hBE!@YUS5?N_tXd=h( z)WE286Fbd>R4M^P{!G)f;h<3Q>Fipuy+d2q-)!RyTgt;wr$(?9ox3;q+{E*ZQHhOn;lM`cjnu9 zXa48ks-v(~b*;MAI<>YZH(^NV8vjb34beE<_cwKlJoR;k6lJNSP6v}uiyRD?|0w+X@o1ONrH8a$fCxXpf? z?$DL0)7|X}Oc%h^zrMKWc-NS9I0Utu@>*j}b@tJ=ixQSJ={4@854wzW@E>VSL+Y{i z#0b=WpbCZS>kUCO_iQz)LoE>P5LIG-hv9E+oG}DtlIDF>$tJ1aw9^LuhLEHt?BCj& z(O4I8v1s#HUi5A>nIS-JK{v!7dJx)^Yg%XjNmlkWAq2*cv#tHgz`Y(bETc6CuO1VkN^L-L3j_x<4NqYb5rzrLC-7uOv z!5e`GZt%B782C5-fGnn*GhDF$%(qP<74Z}3xx+{$4cYKy2ikxI7B2N+2r07DN;|-T->nU&!=Cm#rZt%O_5c&1Z%nlWq3TKAW0w zQqemZw_ue--2uKQsx+niCUou?HjD`xhEjjQd3%rrBi82crq*~#uA4+>vR<_S{~5ce z-2EIl?~s z1=GVL{NxP1N3%=AOaC}j_Fv=ur&THz zyO!d9kHq|c73kpq`$+t+8Bw7MgeR5~`d7ChYyGCBWSteTB>8WAU(NPYt2Dk`@#+}= zI4SvLlyk#pBgVigEe`?NG*vl7V6m+<}%FwPV=~PvvA)=#ths==DRTDEYh4V5}Cf$z@#;< zyWfLY_5sP$gc3LLl2x+Ii)#b2nhNXJ{R~vk`s5U7Nyu^3yFg&D%Txwj6QezMX`V(x z=C`{76*mNb!qHHs)#GgGZ_7|vkt9izl_&PBrsu@}L`X{95-2jf99K)0=*N)VxBX2q z((vkpP2RneSIiIUEnGb?VqbMb=Zia+rF~+iqslydE34cSLJ&BJW^3knX@M;t*b=EA zNvGzv41Ld_T+WT#XjDB840vovUU^FtN_)G}7v)1lPetgpEK9YS^OWFkPoE{ovj^=@ zO9N$S=G$1ecndT_=5ehth2Lmd1II-PuT~C9`XVePw$y8J#dpZ?Tss<6wtVglm(Ok7 z3?^oi@pPio6l&!z8JY(pJvG=*pI?GIOu}e^EB6QYk$#FJQ%^AIK$I4epJ+9t?KjqA+bkj&PQ*|vLttme+`9G=L% ziadyMw_7-M)hS(3E$QGNCu|o23|%O+VN7;Qggp?PB3K-iSeBa2b}V4_wY`G1Jsfz4 z9|SdB^;|I8E8gWqHKx!vj_@SMY^hLEIbSMCuE?WKq=c2mJK z8LoG-pnY!uhqFv&L?yEuxo{dpMTsmCn)95xanqBrNPTgXP((H$9N${Ow~Is-FBg%h z53;|Y5$MUN)9W2HBe2TD`ct^LHI<(xWrw}$qSoei?}s)&w$;&!14w6B6>Yr6Y8b)S z0r71`WmAvJJ`1h&poLftLUS6Ir zC$bG9!Im_4Zjse)#K=oJM9mHW1{%l8sz$1o?ltdKlLTxWWPB>Vk22czVt|1%^wnN@*!l)}?EgtvhC>vlHm^t+ogpgHI1_$1ox9e;>0!+b(tBrmXRB`PY1vp-R**8N7 zGP|QqI$m(Rdu#=(?!(N}G9QhQ%o!aXE=aN{&wtGP8|_qh+7a_j_sU5|J^)vxq;# zjvzLn%_QPHZZIWu1&mRAj;Sa_97p_lLq_{~j!M9N^1yp3U_SxRqK&JnR%6VI#^E12 z>CdOVI^_9aPK2eZ4h&^{pQs}xsijXgFYRIxJ~N7&BB9jUR1fm!(xl)mvy|3e6-B3j zJn#ajL;bFTYJ2+Q)tDjx=3IklO@Q+FFM}6UJr6km7hj7th9n_&JR7fnqC!hTZoM~T zBeaVFp%)0cbPhejX<8pf5HyRUj2>aXnXBqDJe73~J%P(2C?-RT{c3NjE`)om! zl$uewSgWkE66$Kb34+QZZvRn`fob~Cl9=cRk@Es}KQm=?E~CE%spXaMO6YmrMl%9Q zlA3Q$3|L1QJ4?->UjT&CBd!~ru{Ih^in&JXO=|<6J!&qp zRe*OZ*cj5bHYlz!!~iEKcuE|;U4vN1rk$xq6>bUWD*u(V@8sG^7>kVuo(QL@Ki;yL zWC!FT(q{E8#on>%1iAS0HMZDJg{Z{^!De(vSIq&;1$+b)oRMwA3nc3mdTSG#3uYO_ z>+x;7p4I;uHz?ZB>dA-BKl+t-3IB!jBRgdvAbW!aJ(Q{aT>+iz?91`C-xbe)IBoND z9_Xth{6?(y3rddwY$GD65IT#f3<(0o#`di{sh2gm{dw*#-Vnc3r=4==&PU^hCv$qd zjw;>i&?L*Wq#TxG$mFIUf>eK+170KG;~+o&1;Tom9}}mKo23KwdEM6UonXgc z!6N(@k8q@HPw{O8O!lAyi{rZv|DpgfU{py+j(X_cwpKqcalcqKIr0kM^%Br3SdeD> zHSKV94Yxw;pjzDHo!Q?8^0bb%L|wC;4U^9I#pd5O&eexX+Im{ z?jKnCcsE|H?{uGMqVie_C~w7GX)kYGWAg%-?8|N_1#W-|4F)3YTDC+QSq1s!DnOML3@d`mG%o2YbYd#jww|jD$gotpa)kntakp#K;+yo-_ZF9qrNZw<%#C zuPE@#3RocLgPyiBZ+R_-FJ_$xP!RzWm|aN)S+{$LY9vvN+IW~Kf3TsEIvP+B9Mtm! zpfNNxObWQpLoaO&cJh5>%slZnHl_Q~(-Tfh!DMz(dTWld@LG1VRF`9`DYKhyNv z2pU|UZ$#_yUx_B_|MxUq^glT}O5Xt(Vm4Mr02><%C)@v;vPb@pT$*yzJ4aPc_FZ3z z3}PLoMBIM>q_9U2rl^sGhk1VUJ89=*?7|v`{!Z{6bqFMq(mYiA?%KbsI~JwuqVA9$H5vDE+VocjX+G^%bieqx->s;XWlKcuv(s%y%D5Xbc9+ zc(_2nYS1&^yL*ey664&4`IoOeDIig}y-E~_GS?m;D!xv5-xwz+G`5l6V+}CpeJDi^ z%4ed$qowm88=iYG+(`ld5Uh&>Dgs4uPHSJ^TngXP_V6fPyl~>2bhi20QB%lSd#yYn zO05?KT1z@?^-bqO8Cg`;ft>ilejsw@2%RR7;`$Vs;FmO(Yr3Fp`pHGr@P2hC%QcA|X&N2Dn zYf`MqXdHi%cGR@%y7Rg7?d3?an){s$zA{!H;Ie5exE#c~@NhQUFG8V=SQh%UxUeiV zd7#UcYqD=lk-}sEwlpu&H^T_V0{#G?lZMxL7ih_&{(g)MWBnCZxtXg znr#}>U^6!jA%e}@Gj49LWG@*&t0V>Cxc3?oO7LSG%~)Y5}f7vqUUnQ;STjdDU}P9IF9d9<$;=QaXc zL1^X7>fa^jHBu_}9}J~#-oz3Oq^JmGR#?GO7b9a(=R@fw@}Q{{@`Wy1vIQ#Bw?>@X z-_RGG@wt|%u`XUc%W{J z>iSeiz8C3H7@St3mOr_mU+&bL#Uif;+Xw-aZdNYUpdf>Rvu0i0t6k*}vwU`XNO2he z%miH|1tQ8~ZK!zmL&wa3E;l?!!XzgV#%PMVU!0xrDsNNZUWKlbiOjzH-1Uoxm8E#r`#2Sz;-o&qcqB zC-O_R{QGuynW14@)7&@yw1U}uP(1cov)twxeLus0s|7ayrtT8c#`&2~Fiu2=R;1_4bCaD=*E@cYI>7YSnt)nQc zohw5CsK%m?8Ack)qNx`W0_v$5S}nO|(V|RZKBD+btO?JXe|~^Qqur%@eO~<8-L^9d z=GA3-V14ng9L29~XJ>a5k~xT2152zLhM*@zlp2P5Eu}bywkcqR;ISbas&#T#;HZSf z2m69qTV(V@EkY(1Dk3`}j)JMo%ZVJ*5eB zYOjIisi+igK0#yW*gBGj?@I{~mUOvRFQR^pJbEbzFxTubnrw(Muk%}jI+vXmJ;{Q6 zrSobKD>T%}jV4Ub?L1+MGOD~0Ir%-`iTnWZN^~YPrcP5y3VMAzQ+&en^VzKEb$K!Q z<7Dbg&DNXuow*eD5yMr+#08nF!;%4vGrJI++5HdCFcGLfMW!KS*Oi@=7hFwDG!h2< zPunUEAF+HncQkbfFj&pbzp|MU*~60Z(|Ik%Tn{BXMN!hZOosNIseT?R;A`W?=d?5X zK(FB=9mZusYahp|K-wyb={rOpdn=@;4YI2W0EcbMKyo~-#^?h`BA9~o285%oY zfifCh5Lk$SY@|2A@a!T2V+{^!psQkx4?x0HSV`(w9{l75QxMk!)U52Lbhn{8ol?S) zCKo*7R(z!uk<6*qO=wh!Pul{(qq6g6xW;X68GI_CXp`XwO zxuSgPRAtM8K7}5E#-GM!*ydOOG_{A{)hkCII<|2=ma*71ci_-}VPARm3crFQjLYV! z9zbz82$|l01mv`$WahE2$=fAGWkd^X2kY(J7iz}WGS z@%MyBEO=A?HB9=^?nX`@nh;7;laAjs+fbo!|K^mE!tOB>$2a_O0y-*uaIn8k^6Y zSbuv;5~##*4Y~+y7Z5O*3w4qgI5V^17u*ZeupVGH^nM&$qmAk|anf*>r zWc5CV;-JY-Z@Uq1Irpb^O`L_7AGiqd*YpGUShb==os$uN3yYvb`wm6d=?T*it&pDk zo`vhw)RZX|91^^Wa_ti2zBFyWy4cJu#g)_S6~jT}CC{DJ_kKpT`$oAL%b^!2M;JgT zM3ZNbUB?}kP(*YYvXDIH8^7LUxz5oE%kMhF!rnPqv!GiY0o}NR$OD=ITDo9r%4E>E0Y^R(rS^~XjWyVI6 zMOR5rPXhTp*G*M&X#NTL`Hu*R+u*QNoiOKg4CtNPrjgH>c?Hi4MUG#I917fx**+pJfOo!zFM&*da&G_x)L(`k&TPI*t3e^{crd zX<4I$5nBQ8Ax_lmNRa~E*zS-R0sxkz`|>7q_?*e%7bxqNm3_eRG#1ae3gtV9!fQpY z+!^a38o4ZGy9!J5sylDxZTx$JmG!wg7;>&5H1)>f4dXj;B+@6tMlL=)cLl={jLMxY zbbf1ax3S4>bwB9-$;SN2?+GULu;UA-35;VY*^9Blx)Jwyb$=U!D>HhB&=jSsd^6yw zL)?a|>GxU!W}ocTC(?-%z3!IUhw^uzc`Vz_g>-tv)(XA#JK^)ZnC|l1`@CdX1@|!| z_9gQ)7uOf?cR@KDp97*>6X|;t@Y`k_N@)aH7gY27)COv^P3ya9I{4z~vUjLR9~z1Z z5=G{mVtKH*&$*t0@}-i_v|3B$AHHYale7>E+jP`ClqG%L{u;*ff_h@)al?RuL7tOO z->;I}>%WI{;vbLP3VIQ^iA$4wl6@0sDj|~112Y4OFjMs`13!$JGkp%b&E8QzJw_L5 zOnw9joc0^;O%OpF$Qp)W1HI!$4BaXX84`%@#^dk^hFp^pQ@rx4g(8Xjy#!X%+X5Jd@fs3amGT`}mhq#L97R>OwT5-m|h#yT_-v@(k$q7P*9X~T*3)LTdzP!*B} z+SldbVWrrwQo9wX*%FyK+sRXTa@O?WM^FGWOE?S`R(0P{<6p#f?0NJvnBia?k^fX2 zNQs7K-?EijgHJY}&zsr;qJ<*PCZUd*x|dD=IQPUK_nn)@X4KWtqoJNHkT?ZWL_hF? zS8lp2(q>;RXR|F;1O}EE#}gCrY~#n^O`_I&?&z5~7N;zL0)3Tup`%)oHMK-^r$NT% zbFg|o?b9w(q@)6w5V%si<$!U<#}s#x@0aX-hP>zwS#9*75VXA4K*%gUc>+yzupTDBOKH8WR4V0pM(HrfbQ&eJ79>HdCvE=F z|J>s;;iDLB^3(9}?biKbxf1$lI!*Z%*0&8UUq}wMyPs_hclyQQi4;NUY+x2qy|0J; zhn8;5)4ED1oHwg+VZF|80<4MrL97tGGXc5Sw$wAI#|2*cvQ=jB5+{AjMiDHmhUC*a zlmiZ`LAuAn_}hftXh;`Kq0zblDk8?O-`tnilIh|;3lZp@F_osJUV9`*R29M?7H{Fy z`nfVEIDIWXmU&YW;NjU8)EJpXhxe5t+scf|VXM!^bBlwNh)~7|3?fWwo_~ZFk(22% zTMesYw+LNx3J-_|DM~`v93yXe=jPD{q;li;5PD?Dyk+b? zo21|XpT@)$BM$%F=P9J19Vi&1#{jM3!^Y&fr&_`toi`XB1!n>sbL%U9I5<7!@?t)~ z;&H%z>bAaQ4f$wIzkjH70;<8tpUoxzKrPhn#IQfS%9l5=Iu))^XC<58D!-O z{B+o5R^Z21H0T9JQ5gNJnqh#qH^na|z92=hONIM~@_iuOi|F>jBh-?aA20}Qx~EpDGElELNn~|7WRXRFnw+Wdo`|# zBpU=Cz3z%cUJ0mx_1($X<40XEIYz(`noWeO+x#yb_pwj6)R(__%@_Cf>txOQ74wSJ z0#F3(zWWaR-jMEY$7C*3HJrohc79>MCUu26mfYN)f4M~4gD`}EX4e}A!U}QV8!S47 z6y-U-%+h`1n`*pQuKE%Av0@)+wBZr9mH}@vH@i{v(m-6QK7Ncf17x_D=)32`FOjjo zg|^VPf5c6-!FxN{25dvVh#fog=NNpXz zfB$o+0jbRkHH{!TKhE709f+jI^$3#v1Nmf80w`@7-5$1Iv_`)W^px8P-({xwb;D0y z7LKDAHgX<84?l!I*Dvi2#D@oAE^J|g$3!)x1Ua;_;<@#l1fD}lqU2_tS^6Ht$1Wl} zBESo7o^)9-Tjuz$8YQSGhfs{BQV6zW7dA?0b(Dbt=UnQs&4zHfe_sj{RJ4uS-vQpC zX;Bbsuju4%!o8?&m4UZU@~ZZjeFF6ex2ss5_60_JS_|iNc+R0GIjH1@Z z=rLT9%B|WWgOrR7IiIwr2=T;Ne?30M!@{%Qf8o`!>=s<2CBpCK_TWc(DX51>e^xh8 z&@$^b6CgOd7KXQV&Y4%}_#uN*mbanXq(2=Nj`L7H7*k(6F8s6{FOw@(DzU`4-*77{ zF+dxpv}%mFpYK?>N_2*#Y?oB*qEKB}VoQ@bzm>ptmVS_EC(#}Lxxx730trt0G)#$b zE=wVvtqOct1%*9}U{q<)2?{+0TzZzP0jgf9*)arV)*e!f`|jgT{7_9iS@e)recI#z zbzolURQ+TOzE!ymqvBY7+5NnAbWxvMLsLTwEbFqW=CPyCsmJ}P1^V30|D5E|p3BC5 z)3|qgw@ra7aXb-wsa|l^in~1_fm{7bS9jhVRkYVO#U{qMp z)Wce+|DJ}4<2gp8r0_xfZpMo#{Hl2MfjLcZdRB9(B(A(f;+4s*FxV{1F|4d`*sRNd zp4#@sEY|?^FIJ;tmH{@keZ$P(sLh5IdOk@k^0uB^BWr@pk6mHy$qf&~rI>P*a;h0C{%oA*i!VjWn&D~O#MxN&f@1Po# zKN+ zrGrkSjcr?^R#nGl<#Q722^wbYcgW@{+6CBS<1@%dPA8HC!~a`jTz<`g_l5N1M@9wn9GOAZ>nqNgq!yOCbZ@1z`U_N`Z>}+1HIZxk*5RDc&rd5{3qjRh8QmT$VyS;jK z;AF+r6XnnCp=wQYoG|rT2@8&IvKq*IB_WvS%nt%e{MCFm`&W*#LXc|HrD?nVBo=(8*=Aq?u$sDA_sC_RPDUiQ+wnIJET8vx$&fxkW~kP9qXKt zozR)@xGC!P)CTkjeWvXW5&@2?)qt)jiYWWBU?AUtzAN}{JE1I)dfz~7$;}~BmQF`k zpn11qmObXwRB8&rnEG*#4Xax3XBkKlw(;tb?Np^i+H8m(Wyz9k{~ogba@laiEk;2! zV*QV^6g6(QG%vX5Um#^sT&_e`B1pBW5yVth~xUs#0}nv?~C#l?W+9Lsb_5)!71rirGvY zTIJ$OPOY516Y|_014sNv+Z8cc5t_V=i>lWV=vNu#!58y9Zl&GsMEW#pPYPYGHQ|;vFvd*9eM==$_=vc7xnyz0~ zY}r??$<`wAO?JQk@?RGvkWVJlq2dk9vB(yV^vm{=NVI8dhsX<)O(#nr9YD?I?(VmQ z^r7VfUBn<~p3()8yOBjm$#KWx!5hRW)5Jl7wY@ky9lNM^jaT##8QGVsYeaVywmpv>X|Xj7gWE1Ezai&wVLt3p)k4w~yrskT-!PR!kiyQlaxl(( zXhF%Q9x}1TMt3~u@|#wWm-Vq?ZerK={8@~&@9r5JW}r#45#rWii};t`{5#&3$W)|@ zbAf2yDNe0q}NEUvq_Quq3cTjcw z@H_;$hu&xllCI9CFDLuScEMg|x{S7GdV8<&Mq=ezDnRZAyX-8gv97YTm0bg=d)(>N z+B2FcqvI9>jGtnK%eO%y zoBPkJTk%y`8TLf4)IXPBn`U|9>O~WL2C~C$z~9|0m*YH<-vg2CD^SX#&)B4ngOSG$ zV^wmy_iQk>dfN@Pv(ckfy&#ak@MLC7&Q6Ro#!ezM*VEh`+b3Jt%m(^T&p&WJ2Oqvj zs-4nq0TW6cv~(YI$n0UkfwN}kg3_fp?(ijSV#tR9L0}l2qjc7W?i*q01=St0eZ=4h zyGQbEw`9OEH>NMuIe)hVwYHsGERWOD;JxEiO7cQv%pFCeR+IyhwQ|y@&^24k+|8fD zLiOWFNJ2&vu2&`Jv96_z-Cd5RLgmeY3*4rDOQo?Jm`;I_(+ejsPM03!ly!*Cu}Cco zrQSrEDHNyzT(D5s1rZq!8#?f6@v6dB7a-aWs(Qk>N?UGAo{gytlh$%_IhyL7h?DLXDGx zgxGEBQoCAWo-$LRvM=F5MTle`M})t3vVv;2j0HZY&G z22^iGhV@uaJh(XyyY%} zd4iH_UfdV#T=3n}(Lj^|n;O4|$;xhu*8T3hR1mc_A}fK}jfZ7LX~*n5+`8N2q#rI$ z@<_2VANlYF$vIH$ zl<)+*tIWW78IIINA7Rr7i{<;#^yzxoLNkXL)eSs=%|P>$YQIh+ea_3k z_s7r4%j7%&*NHSl?R4k%1>Z=M9o#zxY!n8sL5>BO-ZP;T3Gut>iLS@U%IBrX6BA3k z)&@q}V8a{X<5B}K5s(c(LQ=%v1ocr`t$EqqY0EqVjr65usa=0bkf|O#ky{j3)WBR(((L^wmyHRzoWuL2~WTC=`yZ zn%VX`L=|Ok0v7?s>IHg?yArBcync5rG#^+u)>a%qjES%dRZoIyA8gQ;StH z1Ao7{<&}6U=5}4v<)1T7t!J_CL%U}CKNs-0xWoTTeqj{5{?Be$L0_tk>M9o8 zo371}S#30rKZFM{`H_(L`EM9DGp+Mifk&IP|C2Zu_)Ghr4Qtpmkm1osCf@%Z$%t+7 zYH$Cr)Ro@3-QDeQJ8m+x6%;?YYT;k6Z0E-?kr>x33`H%*ueBD7Zx~3&HtWn0?2Wt} zTG}*|v?{$ajzt}xPzV%lL1t-URi8*Zn)YljXNGDb>;!905Td|mpa@mHjIH%VIiGx- zd@MqhpYFu4_?y5N4xiHn3vX&|e6r~Xt> zZG`aGq|yTNjv;9E+Txuoa@A(9V7g?1_T5FzRI;!=NP1Kqou1z5?%X~Wwb{trRfd>i z8&y^H)8YnKyA_Fyx>}RNmQIczT?w2J4SNvI{5J&}Wto|8FR(W;Qw#b1G<1%#tmYzQ zQ2mZA-PAdi%RQOhkHy9Ea#TPSw?WxwL@H@cbkZwIq0B!@ns}niALidmn&W?!Vd4Gj zO7FiuV4*6Mr^2xlFSvM;Cp_#r8UaqIzHJQg_z^rEJw&OMm_8NGAY2)rKvki|o1bH~ z$2IbfVeY2L(^*rMRU1lM5Y_sgrDS`Z??nR2lX;zyR=c%UyGb*%TC-Dil?SihkjrQy~TMv6;BMs7P8il`H7DmpVm@rJ;b)hW)BL)GjS154b*xq-NXq2cwE z^;VP7ua2pxvCmxrnqUYQMH%a%nHmwmI33nJM(>4LznvY*k&C0{8f*%?zggpDgkuz&JBx{9mfb@wegEl2v!=}Sq2Gaty0<)UrOT0{MZtZ~j5y&w zXlYa_jY)I_+VA-^#mEox#+G>UgvM!Ac8zI<%JRXM_73Q!#i3O|)lOP*qBeJG#BST0 zqohi)O!|$|2SeJQo(w6w7%*92S})XfnhrH_Z8qe!G5>CglP=nI7JAOW?(Z29;pXJ9 zR9`KzQ=WEhy*)WH>$;7Cdz|>*i>=##0bB)oU0OR>>N<21e4rMCHDemNi2LD>Nc$;& zQRFthpWniC1J6@Zh~iJCoLOxN`oCKD5Q4r%ynwgUKPlIEd#?QViIqovY|czyK8>6B zSP%{2-<;%;1`#0mG^B(8KbtXF;Nf>K#Di72UWE4gQ%(_26Koiad)q$xRL~?pN71ZZ zujaaCx~jXjygw;rI!WB=xrOJO6HJ!!w}7eiivtCg5K|F6$EXa)=xUC za^JXSX98W`7g-tm@uo|BKj39Dl;sg5ta;4qjo^pCh~{-HdLl6qI9Ix6f$+qiZ$}s= zNguKrU;u+T@ko(Vr1>)Q%h$?UKXCY>3se%&;h2osl2D zE4A9bd7_|^njDd)6cI*FupHpE3){4NQ*$k*cOWZ_?CZ>Z4_fl@n(mMnYK62Q1d@+I zr&O))G4hMihgBqRIAJkLdk(p(D~X{-oBUA+If@B}j& zsHbeJ3RzTq96lB7d($h$xTeZ^gP0c{t!Y0c)aQE;$FY2!mACg!GDEMKXFOPI^)nHZ z`aSPJpvV0|bbrzhWWkuPURlDeN%VT8tndV8?d)eN*i4I@u zVKl^6{?}A?P)Fsy?3oi#clf}L18t;TjNI2>eI&(ezDK7RyqFxcv%>?oxUlonv(px) z$vnPzRH`y5A(x!yOIfL0bmgeMQB$H5wenx~!ujQK*nUBW;@Em&6Xv2%s(~H5WcU2R z;%Nw<$tI)a`Ve!>x+qegJnQsN2N7HaKzrFqM>`6R*gvh%O*-%THt zrB$Nk;lE;z{s{r^PPm5qz(&lM{sO*g+W{sK+m3M_z=4=&CC>T`{X}1Vg2PEfSj2x_ zmT*(x;ov%3F?qoEeeM>dUn$a*?SIGyO8m806J1W1o+4HRhc2`9$s6hM#qAm zChQ87b~GEw{ADfs+5}FJ8+|bIlIv(jT$Ap#hSHoXdd9#w<#cA<1Rkq^*EEkknUd4& zoIWIY)sAswy6fSERVm&!SO~#iN$OgOX*{9@_BWFyJTvC%S++ilSfCrO(?u=Dc?CXZ zzCG&0yVR{Z`|ZF0eEApWEo#s9osV>F{uK{QA@BES#&;#KsScf>y zvs?vIbI>VrT<*!;XmQS=bhq%46-aambZ(8KU-wOO2=en~D}MCToB_u;Yz{)1ySrPZ z@=$}EvjTdzTWU7c0ZI6L8=yP+YRD_eMMos}b5vY^S*~VZysrkq<`cK3>>v%uy7jgq z0ilW9KjVDHLv0b<1K_`1IkbTOINs0=m-22c%M~l=^S}%hbli-3?BnNq?b`hx^HX2J zIe6ECljRL0uBWb`%{EA=%!i^4sMcj+U_TaTZRb+~GOk z^ZW!nky0n*Wb*r+Q|9H@ml@Z5gU&W`(z4-j!OzC1wOke`TRAYGZVl$PmQ16{3196( zO*?`--I}Qf(2HIwb2&1FB^!faPA2=sLg(@6P4mN)>Dc3i(B0;@O-y2;lM4akD>@^v z=u>*|!s&9zem70g7zfw9FXl1bpJW(C#5w#uy5!V?Q(U35A~$dR%LDVnq@}kQm13{} zd53q3N(s$Eu{R}k2esbftfjfOITCL;jWa$}(mmm}d(&7JZ6d3%IABCapFFYjdEjdK z&4Edqf$G^MNAtL=uCDRs&Fu@FXRgX{*0<(@c3|PNHa>L%zvxWS={L8%qw`STm+=Rd zA}FLspESSIpE_^41~#5yI2bJ=9`oc;GIL!JuW&7YetZ?0H}$$%8rW@*J37L-~Rsx!)8($nI4 zZhcZ2^=Y+p4YPl%j!nFJA|*M^gc(0o$i3nlphe+~-_m}jVkRN{spFs(o0ajW@f3K{ zDV!#BwL322CET$}Y}^0ixYj2w>&Xh12|R8&yEw|wLDvF!lZ#dOTHM9pK6@Nm-@9Lnng4ZHBgBSrr7KI8YCC9DX5Kg|`HsiwJHg2(7#nS;A{b3tVO?Z% za{m5b3rFV6EpX;=;n#wltDv1LE*|g5pQ+OY&*6qCJZc5oDS6Z6JD#6F)bWxZSF@q% z+1WV;m!lRB!n^PC>RgQCI#D1br_o^#iPk>;K2hB~0^<~)?p}LG%kigm@moD#q3PE+ zA^Qca)(xnqw6x>XFhV6ku9r$E>bWNrVH9fum0?4s?Rn2LG{Vm_+QJHse6xa%nzQ?k zKug4PW~#Gtb;#5+9!QBgyB@q=sk9=$S{4T>wjFICStOM?__fr+Kei1 z3j~xPqW;W@YkiUM;HngG!;>@AITg}vAE`M2Pj9Irl4w1fo4w<|Bu!%rh%a(Ai^Zhi zs92>v5;@Y(Zi#RI*ua*h`d_7;byQSa*v9E{2x$<-_=5Z<7{%)}4XExANcz@rK69T0x3%H<@frW>RA8^swA+^a(FxK| zFl3LD*ImHN=XDUkrRhp6RY5$rQ{bRgSO*(vEHYV)3Mo6Jy3puiLmU&g82p{qr0F?ohmbz)f2r{X2|T2 z$4fdQ=>0BeKbiVM!e-lIIs8wVTuC_m7}y4A_%ikI;Wm5$9j(^Y z(cD%U%k)X>_>9~t8;pGzL6L-fmQO@K; zo&vQzMlgY95;1BSkngY)e{`n0!NfVgf}2mB3t}D9@*N;FQ{HZ3Pb%BK6;5#-O|WI( zb6h@qTLU~AbVW#_6?c!?Dj65Now7*pU{h!1+eCV^KCuPAGs28~3k@ueL5+u|Z-7}t z9|lskE`4B7W8wMs@xJa{#bsCGDFoRSNSnmNYB&U7 zVGKWe%+kFB6kb)e;TyHfqtU6~fRg)f|>=5(N36)0+C z`hv65J<$B}WUc!wFAb^QtY31yNleq4dzmG`1wHTj=c*=hay9iD071Hc?oYoUk|M*_ zU1GihAMBsM@5rUJ(qS?9ZYJ6@{bNqJ`2Mr+5#hKf?doa?F|+^IR!8lq9)wS3tF_9n zW_?hm)G(M+MYb?V9YoX^_mu5h-LP^TL^!Q9Z7|@sO(rg_4+@=PdI)WL(B7`!K^ND- z-uIuVDCVEdH_C@c71YGYT^_Scf_dhB8Z2Xy6vGtBSlYud9vggOqv^L~F{BraSE_t} zIkP+Hp2&nH^-MNEs}^`oMLy11`PQW$T|K(`Bu*(f@)mv1-qY(_YG&J2M2<7k;;RK~ zL{Fqj9yCz8(S{}@c)S!65aF<=&eLI{hAMErCx&>i7OeDN>okvegO87OaG{Jmi<|}D zaT@b|0X{d@OIJ7zvT>r+eTzgLq~|Dpu)Z&db-P4z*`M$UL51lf>FLlq6rfG)%doyp z)3kk_YIM!03eQ8Vu_2fg{+osaEJPtJ-s36R+5_AEG12`NG)IQ#TF9c@$99%0iye+ zUzZ57=m2)$D(5Nx!n)=5Au&O0BBgwxIBaeI(mro$#&UGCr<;C{UjJVAbVi%|+WP(a zL$U@TYCxJ=1{Z~}rnW;7UVb7+ZnzgmrogDxhjLGo>c~MiJAWs&&;AGg@%U?Y^0JhL ze(x6Z74JG6FlOFK(T}SXQfhr}RIFl@QXKnIcXYF)5|V~e-}suHILKT-k|<*~Ij|VF zC;t@=uj=hot~*!C68G8hTA%8SzOfETOXQ|3FSaIEjvBJp(A)7SWUi5!Eu#yWgY+;n zlm<$+UDou*V+246_o#V4kMdto8hF%%Lki#zPh}KYXmMf?hrN0;>Mv%`@{0Qn`Ujp) z=lZe+13>^Q!9zT);H<(#bIeRWz%#*}sgUX9P|9($kexOyKIOc`dLux}c$7It4u|Rl z6SSkY*V~g_B-hMPo_ak>>z@AVQ(_N)VY2kB3IZ0G(iDUYw+2d7W^~(Jq}KY=JnWS( z#rzEa&0uNhJ>QE8iiyz;n2H|SV#Og+wEZv=f2%1ELX!SX-(d3tEj$5$1}70Mp<&eI zCkfbByL7af=qQE@5vDVxx1}FSGt_a1DoE3SDI+G)mBAna)KBG4p8Epxl9QZ4BfdAN zFnF|Y(umr;gRgG6NLQ$?ZWgllEeeq~z^ZS7L?<(~O&$5|y)Al^iMKy}&W+eMm1W z7EMU)u^ke(A1#XCV>CZ71}P}0x)4wtHO8#JRG3MA-6g=`ZM!FcICCZ{IEw8Dm2&LQ z1|r)BUG^0GzI6f946RrBlfB1Vs)~8toZf~7)+G;pv&XiUO(%5bm)pl=p>nV^o*;&T z;}@oZSibzto$arQgfkp|z4Z($P>dTXE{4O=vY0!)kDO* zGF8a4wq#VaFpLfK!iELy@?-SeRrdz%F*}hjKcA*y@mj~VD3!it9lhRhX}5YOaR9$} z3mS%$2Be7{l(+MVx3 z(4?h;P!jnRmX9J9sYN#7i=iyj_5q7n#X(!cdqI2lnr8T$IfOW<_v`eB!d9xY1P=2q&WtOXY=D9QYteP)De?S4}FK6#6Ma z=E*V+#s8>L;8aVroK^6iKo=MH{4yEZ_>N-N z`(|;aOATba1^asjxlILk<4}f~`39dBFlxj>Dw(hMYKPO3EEt1@S`1lxFNM+J@uB7T zZ8WKjz7HF1-5&2=l=fqF-*@>n5J}jIxdDwpT?oKM3s8Nr`x8JnN-kCE?~aM1H!hAE z%%w(3kHfGwMnMmNj(SU(w42OrC-euI>Dsjk&jz3ts}WHqmMpzQ3vZrsXrZ|}+MHA7 z068obeXZTsO*6RS@o3x80E4ok``rV^Y3hr&C1;|ZZ0|*EKO`$lECUYG2gVFtUTw)R z4Um<0ZzlON`zTdvVdL#KFoMFQX*a5wM0Czp%wTtfK4Sjs)P**RW&?lP$(<}q%r68Z zS53Y!d@&~ne9O)A^tNrXHhXBkj~$8j%pT1%%mypa9AW5E&s9)rjF4@O3ytH{0z6riz|@< zB~UPh*wRFg2^7EbQrHf0y?E~dHlkOxof_a?M{LqQ^C!i2dawHTPYUE=X@2(3<=OOxs8qn_(y>pU>u^}3y&df{JarR0@VJn0f+U%UiF=$Wyq zQvnVHESil@d|8&R<%}uidGh7@u^(%?$#|&J$pvFC-n8&A>utA=n3#)yMkz+qnG3wd zP7xCnF|$9Dif@N~L)Vde3hW8W!UY0BgT2v(wzp;tlLmyk2%N|0jfG$%<;A&IVrOI< z!L)o>j>;dFaqA3pL}b-Je(bB@VJ4%!JeX@3x!i{yIeIso^=n?fDX`3bU=eG7sTc%g%ye8$v8P@yKE^XD=NYxTb zbf!Mk=h|otpqjFaA-vs5YOF-*GwWPc7VbaOW&stlANnCN8iftFMMrUdYNJ_Bnn5Vt zxfz@Ah|+4&P;reZxp;MmEI7C|FOv8NKUm8njF7Wb6Gi7DeODLl&G~}G4be&*Hi0Qw z5}77vL0P+7-B%UL@3n1&JPxW^d@vVwp?u#gVcJqY9#@-3X{ok#UfW3<1fb%FT`|)V~ggq z(3AUoUS-;7)^hCjdT0Kf{i}h)mBg4qhtHHBti=~h^n^OTH5U*XMgDLIR@sre`AaB$ zg)IGBET_4??m@cx&c~bA80O7B8CHR7(LX7%HThkeC*@vi{-pL%e)yXp!B2InafbDF zjPXf1mko3h59{lT6EEbxKO1Z5GF71)WwowO6kY|6tjSVSWdQ}NsK2x{>i|MKZK8%Q zfu&_0D;CO-Jg0#YmyfctyJ!mRJp)e#@O0mYdp|8x;G1%OZQ3Q847YWTyy|%^cpA;m zze0(5p{tMu^lDkpe?HynyO?a1$_LJl2L&mpeKu%8YvgRNr=%2z${%WThHG=vrWY@4 zsA`OP#O&)TetZ>s%h!=+CE15lOOls&nvC~$Qz0Ph7tHiP;O$i|eDwpT{cp>+)0-|; zY$|bB+Gbel>5aRN3>c0x)4U=|X+z+{ zn*_p*EQoquRL+=+p;=lm`d71&1NqBz&_ph)MXu(Nv6&XE7(RsS)^MGj5Q?Fwude-(sq zjJ>aOq!7!EN>@(fK7EE#;i_BGvli`5U;r!YA{JRodLBc6-`n8K+Fjgwb%sX;j=qHQ z7&Tr!)!{HXoO<2BQrV9Sw?JRaLXV8HrsNevvnf>Y-6|{T!pYLl7jp$-nEE z#X!4G4L#K0qG_4Z;Cj6=;b|Be$hi4JvMH!-voxqx^@8cXp`B??eFBz2lLD8RRaRGh zn7kUfy!YV~p(R|p7iC1Rdgt$_24i0cd-S8HpG|`@my70g^y`gu%#Tf_L21-k?sRRZHK&at(*ED0P8iw{7?R$9~OF$Ko;Iu5)ur5<->x!m93Eb zFYpIx60s=Wxxw=`$aS-O&dCO_9?b1yKiPCQmSQb>T)963`*U+Ydj5kI(B(B?HNP8r z*bfSBpSu)w(Z3j7HQoRjUG(+d=IaE~tv}y14zHHs|0UcN52fT8V_<@2ep_ee{QgZG zmgp8iv4V{k;~8@I%M3<#B;2R>Ef(Gg_cQM7%}0s*^)SK6!Ym+~P^58*wnwV1BW@eG z4sZLqsUvBbFsr#8u7S1r4teQ;t)Y@jnn_m5jS$CsW1um!p&PqAcc8!zyiXHVta9QC zY~wCwCF0U%xiQPD_INKtTb;A|Zf29(mu9NI;E zc-e>*1%(LSXB`g}kd`#}O;veb<(sk~RWL|f3ljxCnEZDdNSTDV6#Td({6l&y4IjKF z^}lIUq*ZUqgTPumD)RrCN{M^jhY>E~1pn|KOZ5((%F)G|*ZQ|r4zIbrEiV%42hJV8 z3xS)=!X1+=olbdGJ=yZil?oXLct8FM{(6ikLL3E%=q#O6(H$p~gQu6T8N!plf!96| z&Q3=`L~>U0zZh;z(pGR2^S^{#PrPxTRHD1RQOON&f)Siaf`GLj#UOk&(|@0?zm;Sx ztsGt8=29-MZs5CSf1l1jNFtNt5rFNZxJPvkNu~2}7*9468TWm>nN9TP&^!;J{-h)_ z7WsHH9|F%I`Pb!>KAS3jQWKfGivTVkMJLO-HUGM_a4UQ_%RgL6WZvrW+Z4ujZn;y@ zz9$=oO!7qVTaQAA^BhX&ZxS*|5dj803M=k&2%QrXda`-Q#IoZL6E(g+tN!6CA!CP* zCpWtCujIea)ENl0liwVfj)Nc<9mV%+e@=d`haoZ*`B7+PNjEbXBkv=B+Pi^~L#EO$D$ZqTiD8f<5$eyb54-(=3 zh)6i8i|jp(@OnRrY5B8t|LFXFQVQ895n*P16cEKTrT*~yLH6Z4e*bZ5otpRDri&+A zfNbK1D5@O=sm`fN=WzWyse!za5n%^+6dHPGX#8DyIK>?9qyX}2XvBWVqbP%%D)7$= z=#$WulZlZR<{m#gU7lwqK4WS1Ne$#_P{b17qe$~UOXCl>5b|6WVh;5vVnR<%d+Lnp z$uEmML38}U4vaW8>shm6CzB(Wei3s#NAWE3)a2)z@i{4jTn;;aQS)O@l{rUM`J@K& l00vQ5JBs~;vo!vr%%-k{2_Fq1Mn4QF81S)AQ99zk{{c4yR+0b! literal 0 HcmV?d00001 diff --git a/simulation/samples/JavaAutoSample/gradle/wrapper/gradle-wrapper.properties b/simulation/samples/JavaAutoSample/gradle/wrapper/gradle-wrapper.properties new file mode 100644 index 0000000000..5e82d67b9f --- /dev/null +++ b/simulation/samples/JavaAutoSample/gradle/wrapper/gradle-wrapper.properties @@ -0,0 +1,7 @@ +distributionBase=GRADLE_USER_HOME +distributionPath=permwrapper/dists +distributionUrl=https\://services.gradle.org/distributions/gradle-8.5-bin.zip +networkTimeout=10000 +validateDistributionUrl=true +zipStoreBase=GRADLE_USER_HOME +zipStorePath=permwrapper/dists diff --git a/simulation/samples/JavaAutoSample/gradlew b/simulation/samples/JavaAutoSample/gradlew new file mode 100644 index 0000000000..1aa94a4269 --- /dev/null +++ b/simulation/samples/JavaAutoSample/gradlew @@ -0,0 +1,249 @@ +#!/bin/sh + +# +# Copyright © 2015-2021 the original authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# https://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# + +############################################################################## +# +# Gradle start up script for POSIX generated by Gradle. +# +# Important for running: +# +# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is +# noncompliant, but you have some other compliant shell such as ksh or +# bash, then to run this script, type that shell name before the whole +# command line, like: +# +# ksh Gradle +# +# Busybox and similar reduced shells will NOT work, because this script +# requires all of these POSIX shell features: +# * functions; +# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», +# «${var#prefix}», «${var%suffix}», and «$( cmd )»; +# * compound commands having a testable exit status, especially «case»; +# * various built-in commands including «command», «set», and «ulimit». +# +# Important for patching: +# +# (2) This script targets any POSIX shell, so it avoids extensions provided +# by Bash, Ksh, etc; in particular arrays are avoided. +# +# The "traditional" practice of packing multiple parameters into a +# space-separated string is a well documented source of bugs and security +# problems, so this is (mostly) avoided, by progressively accumulating +# options in "$@", and eventually passing that to Java. +# +# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS, +# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly; +# see the in-line comments for details. +# +# There are tweaks for specific operating systems such as AIX, CygWin, +# Darwin, MinGW, and NonStop. +# +# (3) This script is generated from the Groovy template +# https://github.com/gradle/gradle/blob/HEAD/subprojects/plugins/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt +# within the Gradle project. +# +# You can find Gradle at https://github.com/gradle/gradle/. +# +############################################################################## + +# Attempt to set APP_HOME + +# Resolve links: $0 may be a link +app_path=$0 + +# Need this for daisy-chained symlinks. +while + APP_HOME=${app_path%"${app_path##*/}"} # leaves a trailing /; empty if no leading path + [ -h "$app_path" ] +do + ls=$( ls -ld "$app_path" ) + link=${ls#*' -> '} + case $link in #( + /*) app_path=$link ;; #( + *) app_path=$APP_HOME$link ;; + esac +done + +# This is normally unused +# shellcheck disable=SC2034 +APP_BASE_NAME=${0##*/} +# Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036) +APP_HOME=$( cd "${APP_HOME:-./}" > /dev/null && pwd -P ) || exit + +# Use the maximum available, or set MAX_FD != -1 to use that value. +MAX_FD=maximum + +warn () { + echo "$*" +} >&2 + +die () { + echo + echo "$*" + echo + exit 1 +} >&2 + +# OS specific support (must be 'true' or 'false'). +cygwin=false +msys=false +darwin=false +nonstop=false +case "$( uname )" in #( + CYGWIN* ) cygwin=true ;; #( + Darwin* ) darwin=true ;; #( + MSYS* | MINGW* ) msys=true ;; #( + NONSTOP* ) nonstop=true ;; +esac + +CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar + + +# Determine the Java command to use to start the JVM. +if [ -n "$JAVA_HOME" ] ; then + if [ -x "$JAVA_HOME/jre/sh/java" ] ; then + # IBM's JDK on AIX uses strange locations for the executables + JAVACMD=$JAVA_HOME/jre/sh/java + else + JAVACMD=$JAVA_HOME/bin/java + fi + if [ ! -x "$JAVACMD" ] ; then + die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." + fi +else + JAVACMD=java + if ! command -v java >/dev/null 2>&1 + then + die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." + fi +fi + +# Increase the maximum file descriptors if we can. +if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then + case $MAX_FD in #( + max*) + # In POSIX sh, ulimit -H is undefined. That's why the result is checked to see if it worked. + # shellcheck disable=SC2039,SC3045 + MAX_FD=$( ulimit -H -n ) || + warn "Could not query maximum file descriptor limit" + esac + case $MAX_FD in #( + '' | soft) :;; #( + *) + # In POSIX sh, ulimit -n is undefined. That's why the result is checked to see if it worked. + # shellcheck disable=SC2039,SC3045 + ulimit -n "$MAX_FD" || + warn "Could not set maximum file descriptor limit to $MAX_FD" + esac +fi + +# Collect all arguments for the java command, stacking in reverse order: +# * args from the command line +# * the main class name +# * -classpath +# * -D...appname settings +# * --module-path (only if needed) +# * DEFAULT_JVM_OPTS, JAVA_OPTS, and GRADLE_OPTS environment variables. + +# For Cygwin or MSYS, switch paths to Windows format before running java +if "$cygwin" || "$msys" ; then + APP_HOME=$( cygpath --path --mixed "$APP_HOME" ) + CLASSPATH=$( cygpath --path --mixed "$CLASSPATH" ) + + JAVACMD=$( cygpath --unix "$JAVACMD" ) + + # Now convert the arguments - kludge to limit ourselves to /bin/sh + for arg do + if + case $arg in #( + -*) false ;; # don't mess with options #( + /?*) t=${arg#/} t=/${t%%/*} # looks like a POSIX filepath + [ -e "$t" ] ;; #( + *) false ;; + esac + then + arg=$( cygpath --path --ignore --mixed "$arg" ) + fi + # Roll the args list around exactly as many times as the number of + # args, so each arg winds up back in the position where it started, but + # possibly modified. + # + # NB: a `for` loop captures its iteration list before it begins, so + # changing the positional parameters here affects neither the number of + # iterations, nor the values presented in `arg`. + shift # remove old arg + set -- "$@" "$arg" # push replacement arg + done +fi + + +# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' + +# Collect all arguments for the java command: +# * DEFAULT_JVM_OPTS, JAVA_OPTS, JAVA_OPTS, and optsEnvironmentVar are not allowed to contain shell fragments, +# and any embedded shellness will be escaped. +# * For example: A user cannot expect ${Hostname} to be expanded, as it is an environment variable and will be +# treated as '${Hostname}' itself on the command line. + +set -- \ + "-Dorg.gradle.appname=$APP_BASE_NAME" \ + -classpath "$CLASSPATH" \ + org.gradle.wrapper.GradleWrapperMain \ + "$@" + +# Stop when "xargs" is not available. +if ! command -v xargs >/dev/null 2>&1 +then + die "xargs is not available" +fi + +# Use "xargs" to parse quoted args. +# +# With -n1 it outputs one arg per line, with the quotes and backslashes removed. +# +# In Bash we could simply go: +# +# readarray ARGS < <( xargs -n1 <<<"$var" ) && +# set -- "${ARGS[@]}" "$@" +# +# but POSIX shell has neither arrays nor command substitution, so instead we +# post-process each arg (as a line of input to sed) to backslash-escape any +# character that might be a shell metacharacter, then use eval to reverse +# that process (while maintaining the separation between arguments), and wrap +# the whole thing up as a single "set" statement. +# +# This will of course break if any of these variables contains a newline or +# an unmatched quote. +# + +eval "set -- $( + printf '%s\n' "$DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS" | + xargs -n1 | + sed ' s~[^-[:alnum:]+,./:=@_]~\\&~g; ' | + tr '\n' ' ' + )" '"$@"' + +exec "$JAVACMD" "$@" diff --git a/simulation/samples/JavaAutoSample/gradlew.bat b/simulation/samples/JavaAutoSample/gradlew.bat new file mode 100644 index 0000000000..93e3f59f13 --- /dev/null +++ b/simulation/samples/JavaAutoSample/gradlew.bat @@ -0,0 +1,92 @@ +@rem +@rem Copyright 2015 the original author or authors. +@rem +@rem Licensed under the Apache License, Version 2.0 (the "License"); +@rem you may not use this file except in compliance with the License. +@rem You may obtain a copy of the License at +@rem +@rem https://www.apache.org/licenses/LICENSE-2.0 +@rem +@rem Unless required by applicable law or agreed to in writing, software +@rem distributed under the License is distributed on an "AS IS" BASIS, +@rem WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +@rem See the License for the specific language governing permissions and +@rem limitations under the License. +@rem + +@if "%DEBUG%"=="" @echo off +@rem ########################################################################## +@rem +@rem Gradle startup script for Windows +@rem +@rem ########################################################################## + +@rem Set local scope for the variables with windows NT shell +if "%OS%"=="Windows_NT" setlocal + +set DIRNAME=%~dp0 +if "%DIRNAME%"=="" set DIRNAME=. +@rem This is normally unused +set APP_BASE_NAME=%~n0 +set APP_HOME=%DIRNAME% + +@rem Resolve any "." and ".." in APP_HOME to make it shorter. +for %%i in ("%APP_HOME%") do set APP_HOME=%%~fi + +@rem Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +set DEFAULT_JVM_OPTS="-Xmx64m" "-Xms64m" + +@rem Find java.exe +if defined JAVA_HOME goto findJavaFromJavaHome + +set JAVA_EXE=java.exe +%JAVA_EXE% -version >NUL 2>&1 +if %ERRORLEVEL% equ 0 goto execute + +echo. +echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. +echo. +echo Please set the JAVA_HOME variable in your environment to match the +echo location of your Java installation. + +goto fail + +:findJavaFromJavaHome +set JAVA_HOME=%JAVA_HOME:"=% +set JAVA_EXE=%JAVA_HOME%/bin/java.exe + +if exist "%JAVA_EXE%" goto execute + +echo. +echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% +echo. +echo Please set the JAVA_HOME variable in your environment to match the +echo location of your Java installation. + +goto fail + +:execute +@rem Setup the command line + +set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar + + +@rem Execute Gradle +"%JAVA_EXE%" %DEFAULT_JVM_OPTS% %JAVA_OPTS% %GRADLE_OPTS% "-Dorg.gradle.appname=%APP_BASE_NAME%" -classpath "%CLASSPATH%" org.gradle.wrapper.GradleWrapperMain %* + +:end +@rem End local scope for the variables with windows NT shell +if %ERRORLEVEL% equ 0 goto mainEnd + +:fail +rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of +rem the _cmd.exe /c_ return code! +set EXIT_CODE=%ERRORLEVEL% +if %EXIT_CODE% equ 0 set EXIT_CODE=1 +if not ""=="%GRADLE_EXIT_CONSOLE%" exit %EXIT_CODE% +exit /b %EXIT_CODE% + +:mainEnd +if "%OS%"=="Windows_NT" endlocal + +:omega diff --git a/simulation/samples/JavaAutoSample/settings.gradle b/simulation/samples/JavaAutoSample/settings.gradle new file mode 100644 index 0000000000..d94f73c635 --- /dev/null +++ b/simulation/samples/JavaAutoSample/settings.gradle @@ -0,0 +1,30 @@ +import org.gradle.internal.os.OperatingSystem + +pluginManagement { + repositories { + mavenLocal() + gradlePluginPortal() + String frcYear = '2024' + File frcHome + if (OperatingSystem.current().isWindows()) { + String publicFolder = System.getenv('PUBLIC') + if (publicFolder == null) { + publicFolder = "C:\\Users\\Public" + } + def homeRoot = new File(publicFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } else { + def userFolder = System.getProperty("user.home") + def homeRoot = new File(userFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } + def frcHomeMaven = new File(frcHome, 'maven') + maven { + name 'frcHome' + url frcHomeMaven + } + } +} + +Properties props = System.getProperties(); +props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/simulation/samples/JavaAutoSample/src/main/deploy/example.txt b/simulation/samples/JavaAutoSample/src/main/deploy/example.txt new file mode 100644 index 0000000000..bb82515dad --- /dev/null +++ b/simulation/samples/JavaAutoSample/src/main/deploy/example.txt @@ -0,0 +1,3 @@ +Files placed in this directory will be deployed to the RoboRIO into the +'deploy' directory in the home folder. Use the 'Filesystem.getDeployDirectory' wpilib function +to get a proper path relative to the deploy directory. \ No newline at end of file diff --git a/simulation/samples/JavaAutoSample/src/main/java/frc/robot/Main.java b/simulation/samples/JavaAutoSample/src/main/java/frc/robot/Main.java new file mode 100644 index 0000000000..8776e5dda7 --- /dev/null +++ b/simulation/samples/JavaAutoSample/src/main/java/frc/robot/Main.java @@ -0,0 +1,25 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot; + +import edu.wpi.first.wpilibj.RobotBase; + +/** + * Do NOT add any static variables to this class, or any initialization at all. Unless you know what + * you are doing, do not modify this file except to change the parameter class to the startRobot + * call. + */ +public final class Main { + private Main() {} + + /** + * Main initialization function. Do not perform any initialization here. + * + *

If you change your main robot class, change the parameter type. + */ + public static void main(String... args) { + RobotBase.startRobot(Robot::new); + } +} diff --git a/simulation/samples/JavaAutoSample/src/main/java/frc/robot/Robot.java b/simulation/samples/JavaAutoSample/src/main/java/frc/robot/Robot.java new file mode 100644 index 0000000000..e8e8733c19 --- /dev/null +++ b/simulation/samples/JavaAutoSample/src/main/java/frc/robot/Robot.java @@ -0,0 +1,161 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot; + +import com.revrobotics.CANSparkLowLevel.MotorType; + +import com.autodesk.synthesis.io.*; + +import edu.wpi.first.wpilibj.SPI; + +import edu.wpi.first.wpilibj.ADXL362; +import edu.wpi.first.wpilibj.TimedRobot; +import edu.wpi.first.wpilibj.motorcontrol.Spark; +import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj.XboxController; + +import com.autodesk.synthesis.revrobotics.CANSparkMax; +import com.kauailabs.navx.frc.AHRS; +import com.autodesk.synthesis.ctre.TalonFX; + +/** + * The VM is configured to automatically run this class, and to call the + * functions corresponding to + * each mode, as described in the TimedRobot documentation. If you change the + * name of this class or + * the package after creating this project, you must also update the + * build.gradle file in the + * project. + */ +public class Robot extends TimedRobot { + private static final String kDefaultAuto = "Default"; + private static final String kCustomAuto = "My Auto"; + private String m_autoSelected; + private final SendableChooser m_chooser = new SendableChooser<>(); + + private ADXL362 m_Accelerometer = new ADXL362(SPI.Port.kMXP, ADXL362.Range.k8G); + private AHRS m_Gyro = new AHRS(); + + private CANSparkMax m_sparkLeft = new CANSparkMax(1, MotorType.kBrushless); + private CANSparkMax m_sparkRight = new CANSparkMax(2, MotorType.kBrushless); + private CANSparkMax m_sparkArm = new CANSparkMax(3, MotorType.kBrushless); + + /** + * This function is run when the robot is first started up and should be used + * for any + * initialization code. + */ + @Override + public void robotInit() { + m_chooser.setDefaultOption("Default Auto", kDefaultAuto); + m_chooser.addOption("My Auto", kCustomAuto); + SmartDashboard.putData("Auto choices", m_chooser); + } + + /** + * This function is called every 20 ms, no matter the mode. Use this for items + * like diagnostics + * that you want ran during disabled, autonomous, teleoperated and test. + * + *

+ * This runs after the mode specific periodic functions, but before LiveWindow + * and + * SmartDashboard integrated updating. + */ + @Override + public void robotPeriodic() { + } + + /** + * This autonomous (along with the chooser code above) shows how to select + * between different + * autonomous modes using the dashboard. The sendable chooser code works with + * the Java + * SmartDashboard. If you prefer the LabVIEW Dashboard, remove all of the + * chooser code and + * uncomment the getString line to get the auto name from the text box below the + * Gyro + * + *

+ * You can add additional auto modes by adding additional comparisons to the + * switch structure + * below with additional strings. If using the SendableChooser make sure to add + * them to the + * chooser code above as well. + */ + @Override + public void autonomousInit() { + m_autoSelected = m_chooser.getSelected(); + // m_autoSelected = SmartDashboard.getString("Auto Selector", kDefaultAuto); + System.out.println("Auto selected: " + m_autoSelected); + m_sparkLeft.getAbsoluteEncoderSim() + } + + enum AutoState { + Stage1, Stage2 + } + + private AutoState m_autoState = AutoState.Stage1; + + /** This function is called periodically during autonomous. */ + @Override + public void autonomousPeriodic() { + switch (m_autoState) { + case Stage1: { + m_sparkLeft.set(0.5); + m_sparkRight.set(0.5); + if (m_sparkLeft.getEncoder()) + break; + } case Stage2: { + break; + } default: { + break; + } + } + m_SparkMax1.set(0.2); + m_SparkMax2.set(-0.2); + } + + /** This function is called once when teleop is enabled. */ + @Override + public void teleopInit() { + } + + /** This function is called periodically during operator control. */ + @Override + public void teleopPeriodic() { + } + + /** This function is called once when the robot is disabled. */ + @Override + public void disabledInit() { + } + + /** This function is called periodically when disabled. */ + @Override + public void disabledPeriodic() { + } + + /** This function is called once when test mode is enabled. */ + @Override + public void testInit() { + } + + /** This function is called periodically during test mode. */ + @Override + public void testPeriodic() { + } + + /** This function is called once when the robot is first started up. */ + @Override + public void simulationInit() { + } + + /** This function is called periodically whilst in simulation. */ + @Override + public void simulationPeriodic() { + } +} diff --git a/simulation/samples/JavaAutoSample/vendordeps/NavX.json b/simulation/samples/JavaAutoSample/vendordeps/NavX.json new file mode 100644 index 0000000000..e978a5f745 --- /dev/null +++ b/simulation/samples/JavaAutoSample/vendordeps/NavX.json @@ -0,0 +1,40 @@ +{ + "fileName": "NavX.json", + "name": "NavX", + "version": "2024.1.0", + "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", + "frcYear": "2024", + "mavenUrls": [ + "https://dev.studica.com/maven/release/2024/" + ], + "jsonUrl": "https://dev.studica.com/releases/2024/NavX.json", + "javaDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-frc-java", + "version": "2024.1.0" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-frc-cpp", + "version": "2024.1.0", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": false, + "libName": "navx_frc", + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "linuxarm32", + "linuxarm64", + "linuxx86-64", + "osxuniversal", + "windowsx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/simulation/samples/JavaAutoSample/vendordeps/Phoenix6.json b/simulation/samples/JavaAutoSample/vendordeps/Phoenix6.json new file mode 100644 index 0000000000..032238505f --- /dev/null +++ b/simulation/samples/JavaAutoSample/vendordeps/Phoenix6.json @@ -0,0 +1,339 @@ +{ + "fileName": "Phoenix6.json", + "name": "CTRE-Phoenix (v6)", + "version": "24.3.0", + "frcYear": 2024, + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json", + "conflictsWith": [ + { + "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a", + "errorMessage": "The combined Phoenix-6-And-5 vendordep is no longer supported. Please remove the vendordep and instead add both the latest Phoenix 6 vendordep and Phoenix 5 vendordep.", + "offlineFileName": "Phoenix6And5.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "24.3.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonFX", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "24.3.0", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "24.3.0", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "24.3.0", + "libName": "CTRE_Phoenix6_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "24.3.0", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "24.3.0", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonFX", + "version": "24.3.0", + "libName": "CTRE_SimTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "24.3.0", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "24.3.0", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "24.3.0", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "24.3.0", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "24.3.0", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "24.3.0", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/simulation/samples/JavaAutoSample/vendordeps/REVLib.json b/simulation/samples/JavaAutoSample/vendordeps/REVLib.json new file mode 100644 index 0000000000..f85acd4054 --- /dev/null +++ b/simulation/samples/JavaAutoSample/vendordeps/REVLib.json @@ -0,0 +1,74 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2024.2.4", + "frcYear": "2024", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2024.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2024.2.4" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2024.2.4", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2024.2.4", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2024.2.4", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file diff --git a/simulation/samples/JavaSample/src/main/java/frc/robot/Robot.java b/simulation/samples/JavaSample/src/main/java/frc/robot/Robot.java index 302f80f47c..f1b05386fc 100644 --- a/simulation/samples/JavaSample/src/main/java/frc/robot/Robot.java +++ b/simulation/samples/JavaSample/src/main/java/frc/robot/Robot.java @@ -100,27 +100,30 @@ public void autonomousInit() { @Override public void autonomousPeriodic() { - m_Spark1.set(0.5); - m_Spark2.set(-0.5); - m_Talon.set(-1.0); - - double position = m_SparkMax1.getAbsoluteEncoderSim().getPosition(); - - if (position >= 20) { - m_SparkMax1.set(0.0); - m_SparkMax2.set(0.0); - m_SparkMax3.set(0.0); - m_SparkMax4.set(0.0); - m_SparkMax5.set(0.0); - m_SparkMax6.set(0.0); - } else { - m_SparkMax1.set(1.0); - m_SparkMax2.set(1.0); - m_SparkMax3.set(1.0); - m_SparkMax4.set(1.0); - m_SparkMax5.set(1.0); - m_SparkMax6.set(1.0); - } + m_SparkMax1.set(0.2); + m_SparkMax2.set(-0.2); + + // m_Spark1.set(0.5); + // m_Spark2.set(-0.5); + // m_Talon.set(-1.0); + + // double position = m_SparkMax1.getAbsoluteEncoderSim().getPosition(); + + // if (position >= 20) { + // m_SparkMax1.set(0.0); + // m_SparkMax2.set(0.0); + // m_SparkMax3.set(0.0); + // m_SparkMax4.set(0.0); + // m_SparkMax5.set(0.0); + // m_SparkMax6.set(0.0); + // } else { + // m_SparkMax1.set(1.0); + // m_SparkMax2.set(1.0); + // m_SparkMax3.set(1.0); + // m_SparkMax4.set(1.0); + // m_SparkMax5.set(1.0); + // m_SparkMax6.set(1.0); + // } switch (m_autoSelected) { case kCustomAuto: @@ -140,11 +143,25 @@ public void teleopInit() { m_AO.setVoltage(6.0); } + private double clamp(double a, double min, double max) { + return Math.min(Math.max(a, min), max); + } + /** This function is called periodically during operator control. */ @Override public void teleopPeriodic() { - m_SparkMax1.set(m_Controller.getLeftY()); - m_SparkMax2.set(-m_Controller.getRightY()); + double forward = -m_Controller.getLeftY(); + double turn = m_Controller.getRightX(); + if (Math.abs(forward) < 0.2) { + forward = 0.0; + } + if (Math.abs(turn) < 0.2) { + turn = 0.0; + } + + m_SparkMax1.set(clamp(forward + turn, -1, 1)); + m_SparkMax2.set(clamp(forward - turn, -1, 1)); + m_Talon.set(m_Controller.getLeftX()); System.out.println("LeftX: " + m_Controller.getLeftX()); // System.out.println("OUT: " + m_DO.get());