diff --git a/exporter/SynthesisFusionAddin/src/Parser/ExporterOptions.py b/exporter/SynthesisFusionAddin/src/Parser/ExporterOptions.py index 39f6c276b..eaa4c4542 100644 --- a/exporter/SynthesisFusionAddin/src/Parser/ExporterOptions.py +++ b/exporter/SynthesisFusionAddin/src/Parser/ExporterOptions.py @@ -53,6 +53,7 @@ class ExporterOptions: exportAsPart: bool = field(default=False) exportLocation: ExportLocation = field(default=ExportLocation.DOWNLOAD) + openSynthesisUponExport: bool = field(default=False) hierarchy: ModelHierarchy = field(default=ModelHierarchy.FusionAssembly) visualQuality: TriangleMeshQualityOptions = field(default=TriangleMeshQualityOptions.LowQualityTriangleMesh) diff --git a/exporter/SynthesisFusionAddin/src/UI/ConfigCommand.py b/exporter/SynthesisFusionAddin/src/UI/ConfigCommand.py index 44d06aabd..1474c4090 100644 --- a/exporter/SynthesisFusionAddin/src/UI/ConfigCommand.py +++ b/exporter/SynthesisFusionAddin/src/UI/ConfigCommand.py @@ -3,12 +3,13 @@ """ import os +import webbrowser from typing import Any import adsk.core import adsk.fusion -from src import gm +from src import APP_WEBSITE_URL, gm from src.APS.APS import getAuth, getUserInfo from src.Logging import getLogger, logFailure from src.Parser.ExporterOptions import ExporterOptions @@ -127,10 +128,10 @@ def notify(self, _: adsk.core.CommandEventArgs) -> None: docName, docVersion = designNameSplit[:2] else: docName = designNameSplit[0] - docVersion = "" + docVersion = "v0" processedFileName = gm.app.activeDocument.name.replace(" ", "_") - defaultFileName = "_".join([docName, docVersion]) + ".mira" if docVersion else f"{docName}.mira" + defaultFileName = f"{'_'.join([docName, docVersion])}.mira" if generalConfigTab.exportLocation == ExportLocation.DOWNLOAD: savepath = FileDialogConfig.saveFileDialog(exporterOptions.fileLocation, defaultFileName) else: @@ -161,6 +162,7 @@ def notify(self, _: adsk.core.CommandEventArgs) -> None: exportAsPart=generalConfigTab.exportAsPart, frictionOverride=generalConfigTab.overrideFriction, frictionOverrideCoeff=generalConfigTab.frictionOverrideCoeff, + openSynthesisUponExport=generalConfigTab.openSynthesisUponExport, ) Parser(exporterOptions).export() @@ -168,6 +170,11 @@ def notify(self, _: adsk.core.CommandEventArgs) -> None: jointConfigTab.reset() gamepieceConfigTab.reset() + if generalConfigTab.openSynthesisUponExport: + res = webbrowser.open(APP_WEBSITE_URL) + if not res: + gm.ui.messageBox("Failed to open Synthesis in your default browser.") + class CommandExecutePreviewHandler(PersistentEventHandler, adsk.core.CommandEventHandler): """Called when an execute command is ready to be previewed.""" diff --git a/exporter/SynthesisFusionAddin/src/UI/GeneralConfigTab.py b/exporter/SynthesisFusionAddin/src/UI/GeneralConfigTab.py index 977f5d929..f73411397 100644 --- a/exporter/SynthesisFusionAddin/src/UI/GeneralConfigTab.py +++ b/exporter/SynthesisFusionAddin/src/UI/GeneralConfigTab.py @@ -110,6 +110,14 @@ def __init__(self, args: adsk.core.CommandCreatedEventArgs, exporterOptions: Exp frictionCoefficient.tooltip = "Friction coefficients range from 0 (ice) to 1 (rubber)." frictionCoefficient.isVisible = exporterOptions.frictionOverride + createBooleanInput( + "openSynthesisOnExportButton", + "Open Synthesis on Export", + generalTabInputs, + checked=exporterOptions.openSynthesisUponExport, + tooltip="Launch the Synthesis website upon export.", + ) + if exporterOptions.exportMode == ExportMode.FIELD: autoCalcWeightButton.isVisible = False exportAsPartButton.isVisible = False @@ -182,6 +190,13 @@ def frictionOverrideCoeff(self) -> float: ) return frictionSlider.valueOne or -1.0 + @property + def openSynthesisUponExport(self) -> bool: + openSynthesisButton: adsk.core.BoolValueCommandInput = self.generalOptionsTab.children.itemById( + "openSynthesisOnExportButton" + ) + return openSynthesisButton.value or False + @logFailure def handleInputChanged(self, args: adsk.core.InputChangedEventArgs) -> None: autoCalcWeightButton: adsk.core.BoolValueCommandInput = args.inputs.itemById("autoCalcWeightButton") diff --git a/exporter/SynthesisFusionAddin/src/__init__.py b/exporter/SynthesisFusionAddin/src/__init__.py index b53fb6b04..42d1e6d39 100644 --- a/exporter/SynthesisFusionAddin/src/__init__.py +++ b/exporter/SynthesisFusionAddin/src/__init__.py @@ -7,6 +7,7 @@ APP_NAME = "Synthesis" APP_TITLE = "Synthesis Robot Exporter" +APP_WEBSITE_URL = "https://synthesis.autodesk.com/fission/" DESCRIPTION = "Exports files from Fusion into the Synthesis Format" INTERNAL_ID = "Synthesis" ADDIN_PATH = os.path.dirname(os.path.realpath(__file__)) diff --git a/fission/src/ui/components/Modal.tsx b/fission/src/ui/components/Modal.tsx index 3dad42319..ad7357bb1 100644 --- a/fission/src/ui/components/Modal.tsx +++ b/fission/src/ui/components/Modal.tsx @@ -56,7 +56,7 @@ const Modal: React.FC = ({
{name && ( diff --git a/fission/src/ui/components/StyledComponents.tsx b/fission/src/ui/components/StyledComponents.tsx index 66e404d71..a42896b75 100644 --- a/fission/src/ui/components/StyledComponents.tsx +++ b/fission/src/ui/components/StyledComponents.tsx @@ -3,7 +3,6 @@ import Label, { LabelSize } from "./Label" import Button, { ButtonProps, ButtonSize } from "./Button" import { IoCheckmark, IoPencil, IoPeople, IoTrashBin } from "react-icons/io5" import { HiDownload } from "react-icons/hi" -import { AiOutlinePlus } from "react-icons/ai" import { BiRefresh } from "react-icons/bi" import { AiFillWarning } from "react-icons/ai" import { BsCodeSquare } from "react-icons/bs" @@ -58,7 +57,8 @@ export class SynthesisIcons { /** Large icons: used for icon buttons */ public static DeleteLarge = () public static DownloadLarge = () - public static AddLarge = () + public static AddLarge = () + public static GearLarge = () public static RefreshLarge = () public static SelectLarge = () public static EditLarge = () diff --git a/fission/src/ui/modals/configuring/SettingsModal.tsx b/fission/src/ui/modals/configuring/SettingsModal.tsx index 006666d7b..6f54dd1f0 100644 --- a/fission/src/ui/modals/configuring/SettingsModal.tsx +++ b/fission/src/ui/modals/configuring/SettingsModal.tsx @@ -1,22 +1,22 @@ import React, { useState } from "react" import Modal, { ModalPropsImpl } from "@/components/Modal" -import { FaGear } from "react-icons/fa6" import Label, { LabelSize } from "@/components/Label" import Dropdown from "@/components/Dropdown" -import Slider from "@/components/Slider" import Checkbox from "@/components/Checkbox" import PreferencesSystem from "@/systems/preferences/PreferencesSystem" import { SceneOverlayEvent, SceneOverlayEventKey } from "@/ui/components/SceneOverlayEvents" import { QualitySetting } from "@/systems/preferences/PreferenceTypes" import { Box } from "@mui/material" -import { Spacer } from "@/ui/components/StyledComponents" +import { Spacer, SynthesisIcons } from "@/ui/components/StyledComponents" import World from "@/systems/World" const SettingsModal: React.FC = ({ modalId }) => { const [qualitySettings, setQualitySettings] = useState( PreferencesSystem.getGlobalPreference("QualitySettings") ) - const [zoomSensitivity, setZoomSensitivity] = useState( + + // Disabled until camera settings are implemented + /* const [zoomSensitivity, setZoomSensitivity] = useState( PreferencesSystem.getGlobalPreference("ZoomSensitivity") ) const [pitchSensitivity, setPitchSensitivity] = useState( @@ -24,11 +24,15 @@ const SettingsModal: React.FC = ({ modalId }) => { ) const [yawSensitivity, setYawSensitivity] = useState( PreferencesSystem.getGlobalPreference("YawSensitivity") - ) + ) */ + const [reportAnalytics, setReportAnalytics] = useState( PreferencesSystem.getGlobalPreference("ReportAnalytics") ) - const [useMetric, setUseMetric] = useState(PreferencesSystem.getGlobalPreference("UseMetric")) + + // Disabled until use metric is implemented + // const [useMetric, setUseMetric] = useState(PreferencesSystem.getGlobalPreference("UseMetric")) + const [renderScoringZones, setRenderScoringZones] = useState( PreferencesSystem.getGlobalPreference("RenderScoringZones") ) @@ -44,29 +48,32 @@ const SettingsModal: React.FC = ({ modalId }) => { const saveSettings = () => { PreferencesSystem.setGlobalPreference("QualitySettings", qualitySettings) - PreferencesSystem.setGlobalPreference("ZoomSensitivity", zoomSensitivity) - PreferencesSystem.setGlobalPreference("PitchSensitivity", pitchSensitivity) - PreferencesSystem.setGlobalPreference("YawSensitivity", yawSensitivity) + PreferencesSystem.setGlobalPreference("ReportAnalytics", reportAnalytics) - PreferencesSystem.setGlobalPreference("UseMetric", useMetric) PreferencesSystem.setGlobalPreference("RenderScoringZones", renderScoringZones) PreferencesSystem.setGlobalPreference("RenderSceneTags", renderSceneTags) PreferencesSystem.setGlobalPreference("RenderScoreboard", renderScoreboard) PreferencesSystem.setGlobalPreference("SubsystemGravity", subsystemGravity) + // Disabled until these settings are implemented + /* PreferencesSystem.setGlobalPreference("ZoomSensitivity", zoomSensitivity) + PreferencesSystem.setGlobalPreference("PitchSensitivity", pitchSensitivity) + PreferencesSystem.setGlobalPreference("YawSensitivity", yawSensitivity) + PreferencesSystem.setGlobalPreference("UseMetric", useMetric) */ + PreferencesSystem.savePreferences() } return ( } + icon={SynthesisIcons.GearLarge} modalId={modalId} onAccept={() => { saveSettings() }} > -
+
= ({ modalId }) => { World.SceneRenderer.ChangeLighting(selected) }} /> - {Spacer(5)} + + {/* Disabled until these settings are implemented */} + {/* {Spacer(5)} = ({ modalId }) => { format={{ maximumFractionDigits: 2 }} onChange={(_, value) => setYawSensitivity(value as number)} tooltipText="Moving the camera left and right." - /> + />*/} {Spacer(20)} @@ -118,13 +127,15 @@ const SettingsModal: React.FC = ({ modalId }) => { }} tooltipText="Record user data such as what robots are spawned and how they are configured. No personal data will be collected." /> - ("UseMetric")} onClick={checked => { setUseMetric(checked) }} - /> + tooltipText="Metric measurements. (ex: meters instead of feet)" + /> */} ("SubsystemGravity")} diff --git a/fission/src/ui/modals/configuring/theme-editor/NewInputSchemeModal.tsx b/fission/src/ui/modals/configuring/theme-editor/NewInputSchemeModal.tsx index 81c59769a..06b95d7a1 100644 --- a/fission/src/ui/modals/configuring/theme-editor/NewInputSchemeModal.tsx +++ b/fission/src/ui/modals/configuring/theme-editor/NewInputSchemeModal.tsx @@ -16,7 +16,7 @@ const NewInputSchemeModal: React.FC = ({ modalId }) => { return ( { const scheme = DefaultInputs.newBlankScheme diff --git a/fission/src/ui/panels/configuring/ChooseInputSchemePanel.tsx b/fission/src/ui/panels/configuring/ChooseInputSchemePanel.tsx index 40a2ed7a8..0d5b549f3 100644 --- a/fission/src/ui/panels/configuring/ChooseInputSchemePanel.tsx +++ b/fission/src/ui/panels/configuring/ChooseInputSchemePanel.tsx @@ -73,7 +73,6 @@ const ChooseInputSchemePanel: React.FC = ({ panelId }) => { sidePadding={8} acceptEnabled={false} icon={SynthesisIcons.Gamepad} - cancelEnabled={selectedBrainIndexGlobal != undefined} cancelName="Close" > {/** A scroll view with buttons to select default and custom input schemes */} diff --git a/fission/src/ui/panels/configuring/assembly-config/interfaces/inputs/ConfigureInputsInterface.tsx b/fission/src/ui/panels/configuring/assembly-config/interfaces/inputs/ConfigureInputsInterface.tsx index 913ad32b4..175bca83a 100644 --- a/fission/src/ui/panels/configuring/assembly-config/interfaces/inputs/ConfigureInputsInterface.tsx +++ b/fission/src/ui/panels/configuring/assembly-config/interfaces/inputs/ConfigureInputsInterface.tsx @@ -77,10 +77,19 @@ const ConfigureInputsInterface = () => { // Fetch current custom schemes InputSchemeManager.saveSchemes() InputSchemeManager.resetDefaultSchemes() - const schemes = PreferencesSystem.getGlobalPreference("InputSchemes") - // Find and remove this input scheme + // Find the scheme to remove in preferences + const schemes = PreferencesSystem.getGlobalPreference("InputSchemes") const index = schemes.indexOf(val.scheme) + + // If currently bound to a robot, remove the binding + for (const [key, value] of InputSystem.brainIndexSchemeMap.entries()) { + if (value == schemes[index]) { + InputSystem.brainIndexSchemeMap.delete(key) + } + } + + // Find and remove this input scheme from preferences schemes.splice(index, 1) // Save to preferences diff --git a/simulation/SyntheSimJava/README.md b/simulation/SyntheSimJava/README.md index 3e10a613a..fff3e72ef 100644 --- a/simulation/SyntheSimJava/README.md +++ b/simulation/SyntheSimJava/README.md @@ -4,21 +4,24 @@ This is the SyntheSim Java utility library. FRC users can add this to their proj ## Current 3rd-Party Support -This is a list of the following 3rd-Party libraries that SyntheSim - Java improves, as well as the level of capability currently offered. +A list of the 3rd-Party libraries SyntheSimJava supports, including the features currently offered. ### REVRobotics -- [ ] CANSparkMax + +- [x] CANSparkMax - [x] Basic motor control - [x] Basic internal encoder data - - [ ] Motor following - - [ ] Full encoder support + - [x] Motor following + - [x] Full encoder support + +### CTRE Phoenix v6 -### CTRE Phoenix -- [ ] TalonFX - - [ ] Basic motor control - - [ ] Basic internal encoder data - - [ ] Motor following - - [ ] Full encoder support +- [x] TalonFX + - [x] Basic motor control + - [x] Full configuration support (via a [TalonFXConfigurator](src/main/com/autodesk/synthesis/ctre/TalonFXConfigurator.java) wrapper) + - [x] Basic internal encoder data + - [x] Motor following + - [x] Full encoder support ## Building @@ -27,15 +30,18 @@ To build the project, run the `build` task:
Example - Windows: - ```sh - $ gradlew.bat build - ``` +Windows: + +```sh +gradlew.bat build +``` + +MacOS/Linux: + +```sh +./gradlew build +``` - MacOS/Linux: - ```sh - $ ./gradlew build - ```
## Usage @@ -49,20 +55,23 @@ To publish the project locally, run the `publishToMavenLocal` task:
Example - Windows: - ```sh - $ gradlew.bat publishToMavenLocal - ``` +Windows: + +```sh +gradlew.bat publishToMavenLocal +``` + +MacOS/Linux: + +```sh +./gradlew publishToMavenLocal +``` - MacOS/Linux: - ```sh - $ ./gradlew publishToMavenLocal - ```
### Adding to project locally -In order to add the project locally, you must include the the `mavenLocal()` repository to your projects: +In order to add the project locally, you must include the `mavenLocal()` repository to your projects: ```groovy repositories { @@ -83,4 +92,6 @@ dependencies { ### Swapping Imports -SyntheSimJava creates alternative classes that wrap the original ones. Everything that we intercept is passed on to the original class, making it so these classes can (although not recommended) be used when running your robot code on original hardware. Be sure to switch over any and all CAN devices that this project supports in order to effectively simulate your code inside of Synthesis, or with any HALSim, WebSocket supported simulation/device. \ No newline at end of file +SyntheSimJava creates alternative classes that wrap the original ones. Everything that we intercept is passed on to the original class, making it so these classes can (although not recommended) be used when running your robot code on original hardware. Be sure to switch over any and all CAN devices that this project supports in order to effectively simulate your code inside of Synthesis, or with any HALSim, WebSocket supported simulation/device. + +The one exception to this is the `CANSparkMax.getAbsoluteEncoder()` method, which you must substitute for the `CANSparkMax.getAbsoluteEncoderSim()` method, because we were unable to override the original, because we are unable to wrap the return type `SparkAbsoluteEncoder`, because it's constructor is private. We instead created a class that implements all the same interfaces and has all the same methods, and thus works exactly the same, except it isn't an explicit subclass of `SparkAbsoluteEncoder`. The only difference to the API is the method name, everything else operates identically. diff --git a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/CANEncoder.java b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/CANEncoder.java index d00e5439b..9b7220a1c 100644 --- a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/CANEncoder.java +++ b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/CANEncoder.java @@ -36,7 +36,7 @@ public CANEncoder(String name, int deviceId) { /** * Gets the current position of the encoder, simulated. * - * @return Current Position. + * @return Current position in revolutions. */ public double getPosition() { return m_position.get(); @@ -45,7 +45,7 @@ public double getPosition() { /** * Gets the current velocity of the encoder, simulated. * - * @return Current Velocity. + * @return Current velocity in revolutions per second. */ public double getVelocity() { return m_velocity.get(); diff --git a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/CANMotor.java b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/CANMotor.java index e4df23ba6..6e5f0ccd0 100644 --- a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/CANMotor.java +++ b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/CANMotor.java @@ -96,7 +96,7 @@ public void setNeutralDeadband(double deadband) { /** * Get the supply current, simulated. * - * @return Supply Current. + * @return Supply current in amps. */ public double getSupplyCurrent() { return m_supplyCurrent.get(); @@ -105,7 +105,7 @@ public double getSupplyCurrent() { /** * Get the motor current, simulated. * - * @return Motor Current. + * @return Motor current in amps. */ public double getMotorCurrent() { return m_motorCurrent.get(); @@ -114,7 +114,7 @@ public double getMotorCurrent() { /** * Get the Bus Voltage, simulated. * - * @return Bus Voltage + * @return Bus voltage */ public double getBusVoltage() { return m_busVoltage.get(); diff --git a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/ctre/TalonFX.java b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/ctre/TalonFX.java index 5e671b86c..92863e701 100644 --- a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/ctre/TalonFX.java +++ b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/ctre/TalonFX.java @@ -22,13 +22,23 @@ public TalonFX(int deviceNumber) { this.m_motor = new CANMotor("SYN TalonFX", deviceNumber, 0.0, false, 0.3); } - /// I think we're getting percentOutput and speed mixed up + /** + * Sets the torque of the real and simulated motors + * + * @param percentOutput The torque + */ @Override public void set(double percentOutput) { super.set(percentOutput); this.m_motor.setPercentOutput(percentOutput); } + /** + * Sets both the real and simulated motors to neutral mode + * + * @param mode The neutral mode value + * + */ @Override public void setNeutralMode(NeutralModeValue mode) { super.setNeutralMode(mode); @@ -36,6 +46,11 @@ public void setNeutralMode(NeutralModeValue mode) { this.m_motor.setBrakeMode(mode == NeutralModeValue.Brake); } + /** + * Gets and internal configurator for both the simulated and real motors + * + * @return The internal configurator for this Talon motor + */ @Override public TalonFXConfigurator getConfigurator() { DeviceIdentifier id = this.deviceIdentifier; @@ -47,6 +62,11 @@ public void setNeutralDeadband(double deadband) { this.m_motor.setNeutralDeadband(deadband); } + /** + * Gets the position of the simulated encoder + * + * @return The motor position in revolutions + */ @Override public StatusSignal getPosition() { Double pos = this.m_encoder.getPosition(); @@ -54,7 +74,11 @@ public StatusSignal getPosition() { return super.getPosition(); } - /// I think this is a pointless method + /** + * Gets the velocity of the simulated motor according to the simulated encoder + * + * @return The motor velocity in revolutions per second + */ @Override public StatusSignal getVelocity() { Double velocity = this.m_encoder.getVelocity(); diff --git a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/ctre/TalonFXConfigurator.java b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/ctre/TalonFXConfigurator.java index 6cc33b28a..11726331e 100644 --- a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/ctre/TalonFXConfigurator.java +++ b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/ctre/TalonFXConfigurator.java @@ -4,16 +4,30 @@ import com.ctre.phoenix6.configs.TorqueCurrentConfigs; import com.ctre.phoenix6.StatusCode; +/** + * TalonFXConfigurator wrapper to add proper WPILib HALSim support. + */ public class TalonFXConfigurator extends com.ctre.phoenix6.configs.TalonFXConfigurator { private TalonFX devicePtr; + /** + * Creates a new TalonFXConfigurator, wrapped with simulation support. + * + * @param id Device ID + * @param device The motor to configure + */ public TalonFXConfigurator(DeviceIdentifier id, TalonFX device) { super(id); // awful, jank solution, please help // if you know how to get a device from an id, let me know this.devicePtr = device; } - + + /** + * Applies a torque configuration to a TalonFX motor and passes the new neutral deadband to the simulated motor in fission if applicable + * + * @param newTorqueCurrent The new torque configuration for this motor + */ @Override public StatusCode apply(TorqueCurrentConfigs newTorqueCurrent) { StatusCode code = super.apply(newTorqueCurrent); 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 560cc5bc7..6cd32aae3 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 @@ -20,8 +20,10 @@ public class CANSparkMax extends com.revrobotics.CANSparkMax { * Creates a new CANSparkMax, wrapped with simulation support. * * @param deviceId CAN Device ID. - * @param motorType Motortype. For Simulation purposes, this is discarded at the + * @param motorType Motor type. For Simulation purposes, this is discarded at the * moment. + * + * See original documentation for more information https://codedocs.revrobotics.com/java/com/revrobotics/cansparkmax */ public CANSparkMax(int deviceId, MotorType motorType) { super(deviceId, motorType); @@ -31,7 +33,14 @@ public CANSparkMax(int deviceId, MotorType motorType) { this.followers = new ArrayList(); } - // setting a follower doesn't break the simulated follower - leader relationship + /** + * 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 + * + * See the original documentation for more information + */ @Override public void set(double percent) { super.set(percent); @@ -41,29 +50,58 @@ public void set(double percent) { } } - public void setNeutralDeadband(double n) { + /** + * Sets the neutralDeadband of the real and simulated motors + * + * @param n The new neutral deadband + */ + void setNeutralDeadband(double n) { this.m_motor.setNeutralDeadband(n); } + /** + * Sets the real and simulated motors to an idle mode + * + * @param mode The specific idle mode (Brake, Coast) + * + * @return A library error indicating failure or success + */ @Override public REVLibError setIdleMode(com.revrobotics.CANSparkBase.IdleMode mode) { - if (mode != null) { + if (mode != null) this.m_motor.setBrakeMode(mode.equals(com.revrobotics.CANSparkBase.IdleMode.kBrake)); - } return super.setIdleMode(mode); } - /// Use instead on getAbsoluteEncoder(), everything else works exactly the same in every way but name + /** + * Gets a simulation-supported SparkAbsoluteEncoder containing the position and velocity of the motor in fission. + * All information returned by this class besides position and velocity is from the real motor. + * Use instead of getAbsoluteEncoder(), everything except for the name of the method works exactly the same. + + * @return The simulation-supported SparkAbsoluteEncoder. + */ public com.autodesk.synthesis.revrobotics.SparkAbsoluteEncoder getAbsoluteEncoderSim() { return new SparkAbsoluteEncoder(super.getAbsoluteEncoder(), this.m_encoder); } - public void newFollower(CANSparkMax f) { + /** + * Adds a follower to this motor controller. + * + * @param f The new follower + */ + void newFollower(CANSparkMax f) { this.followers.add(f); } - // Must pass in a simulation-supported leader to have the simulated portion of this motor follow + /** + * Causes a simulation-supported leader to follow another simulation-supported leader. + * The real versions of these motors will also follow each other. + * + * @param leader The motor for this robot to follow + * + * @return A library error indicating failure or success + */ @Override public REVLibError follow(CANSparkBase leader) { REVLibError err = super.follow(leader); diff --git a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/SparkAbsoluteEncoder.java b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/SparkAbsoluteEncoder.java index e99a73a6d..402bdca0b 100644 --- a/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/SparkAbsoluteEncoder.java +++ b/simulation/SyntheSimJava/src/main/java/com/autodesk/synthesis/revrobotics/SparkAbsoluteEncoder.java @@ -5,64 +5,140 @@ import com.revrobotics.AbsoluteEncoder; import com.revrobotics.REVLibError; +/** + * SparkAbsoluteEncoder wrapper to add proper WPILib HALSim support. + */ public class SparkAbsoluteEncoder implements AbsoluteEncoder { private CANEncoder simEncoder; private com.revrobotics.SparkAbsoluteEncoder realEncoder; - // We're prettys sure that it's impossible to make a child class of this parent class with a constructor, because the parent's constructor is private - // Reflection didn't work since a child constructor __needs__ a super() call at the top of the body - // Passing in the constuctor wouldn't work either, since it's just a function pointer and the child constructor would have no idea that it points to its super + /* + * A SparkAbsoluteEncoder class that returns the motors position and velocity from the simulated motor in fission, rather than the actual motor. + * All other parameters are returned from the real motor, which likely won't exist, not sure what it does then but we'll just call it UB. + */ public SparkAbsoluteEncoder(com.revrobotics.SparkAbsoluteEncoder realEncoder, CANEncoder simEncoder) { this.realEncoder = realEncoder; this.simEncoder = simEncoder; } + /** + * Gets the average sampling depth for the real encoder + * + * @return The average sampling depth + */ public int getAverageDepth() { return this.realEncoder.getAverageDepth(); } + /** + * Gets the phase of the real encoder + * + * @return The phase of the real encoder + */ public boolean getInverted() { return this.realEncoder.getInverted(); } + /** + * Gets the position of the simulated motor. + * This returns the native units of 'rotations' by default, and can be changed by a scale factor using setPositionConversionFactor(). + * + * @return Number of rotations of the motor + */ public double getPosition() { - return this.simEncoder.getPosition() * this.realEncoder.getPositionConversionFactor(); + return this.simEncoder.getPosition(); } - // TODO: Remove conversion factors on the fission end + /** + * Sets the conversion factor for position of the real encoder. Multiplying by the native output units to give you position + * + * @return The conversion factor used by the encoder for position + */ public double getPositionConversionFactor() { - return this.getPositionConversionFactor(); + return this.realEncoder.getPositionConversionFactor(); } - + + + /** + * Gets the velocity of the simulated motor. This returns the native units of 'rotations per second' by default, and can be changed by a scale factor using setVelocityConversionFactor(). + * + * @return Number of rotations per second of the motor + */ public double getVelocity() { return this.simEncoder.getVelocity() * this.realEncoder.getVelocityConversionFactor(); } + + /** + * Gets the conversion factor for velocity of the real encoder. + * + * @return The conversion factor used by the encoder for position + */ public double getVelocityConversionFactor() { return this.realEncoder.getVelocityConversionFactor(); } + /** + * Gets the zero offset in revolutions for the real encoder (the position that is reported as zero). + * + * @return The zero offset + */ public double getZeroOffset() { return this.realEncoder.getZeroOffset(); } - + + /** + * Sets the average sampling depth for the real encoder. + * + * @param depth The average sampling depth + * + * @return A library error indicating failure or success + */ public REVLibError setAverageDepth(int depth) { return this.realEncoder.setAverageDepth(depth); } + /** + * Sets the phase of the real encoder + * + * @param inverted Whether the real motor should be inverted + * + * @return A library error indicating failure or success + */ public REVLibError setInverted(boolean inverted) { return this.realEncoder.setInverted(inverted); } + /** + * Sets the conversion factor for position of the real encoder. + * + * @param factor The new position conversion factor + * + * @return A library error indicating failure or success + */ public REVLibError setPositionConversionFactor(double factor) { return this.realEncoder.setPositionConversionFactor(factor); } + /** + * Sets the conversion factor for velocity of the real encoder. + * + * @param factor The new velocity conversion factor + * + * @return A library error indicating failure or success + */ public REVLibError setVelocityConversionFactor(double factor) { return this.realEncoder.setVelocityConversionFactor(factor); } - public REVLibError setZeroOffset(double factor) { - return this.realEncoder.setZeroOffset(factor); + /** + * Sets the zero offset of the real encoder (the position that is reported as zero). + * + * @param offset The new zero offset + * + * @return A library error indicating failure or success + */ + public REVLibError setZeroOffset(double offset) { + return this.realEncoder.setZeroOffset(offset); } }