From 07d4bdef7fec9f7cd8da612b424c5800384c265b Mon Sep 17 00:00:00 2001 From: kredcool Date: Sun, 10 Mar 2024 16:00:03 -0400 Subject: [PATCH 1/5] this actually have bindings --- rio/pyproject.toml | 2 +- rio/robotcontainer.py | 40 ++++++++++++++++++++++++++++++++++++---- 2 files changed, 37 insertions(+), 5 deletions(-) diff --git a/rio/pyproject.toml b/rio/pyproject.toml index 7030689..453fc4b 100644 --- a/rio/pyproject.toml +++ b/rio/pyproject.toml @@ -6,7 +6,7 @@ [tool.robotpy] # Version of robotpy this project depends on -robotpy_version = "2024.2.1.1" +robotpy_version = "2024.3.1.0" # Which extra RobotPy components should be installed # -> equivalent to `pip install robotpy[extra1, ...] diff --git a/rio/robotcontainer.py b/rio/robotcontainer.py index f500ce8..d8628c9 100644 --- a/rio/robotcontainer.py +++ b/rio/robotcontainer.py @@ -16,7 +16,7 @@ # CommandsV2 import commands2 from commands2 import cmd -from commands2.button import CommandJoystick, CommandXboxController +from commands2.button import CommandXboxController, CommandGenericHID from constants import AutoConstants, DriveConstants, OIConstants, SuperStrucConstants @@ -90,7 +90,7 @@ def __init__(self) -> None: OIConstants.kDriveDeadband, # TODO: Use constants to set these controls ) * 0.6, - False, + True, True, ), self.robotDrive, @@ -165,12 +165,11 @@ def configureButtonBindings(self) -> None: # Operator Commands # ============================== + """ # moving intake self.opController.pov(90).whileTrue(IntakeRotationMAN(1, self.intake)) # out self.opController.pov(270).whileTrue(IntakeRotationMAN(-1, self.intake)) # in - # _____POST_INTAKE_KEYBINDS_____ - # moving shooter self.opController.pov(0).whileTrue(manualROT(0.5, self.shooter)) self.opController.pov(180).whileTrue(manualROT(-0.5, self.shooter)) @@ -190,6 +189,39 @@ def configureButtonBindings(self) -> None: self.opController.back().onTrue( commands2.InstantCommand(self.intake.zeroIntake) ) + """ + + # intake keybinds + # intake movement + self.opController.button(2).whileTrue(IntakeRotationMAN(1, self.intake)) # out + self.opController.button(1).whileTrue(IntakeRotationMAN(-1, self.intake)) # in + + # intake spin + self.opController.button(6).whileTrue(SetIntakeSpeed(0.6, self.intake)) + self.opController.button(9).whileTrue(SetIntakeSpeed(-0.6, self.intake)) + + # shooter keybinds + # shooter movement + self.opController.button(3).whileTrue(manualROT(0.5, self.shooter)) + self.opController.button(4).whileTrue(manualROT(-0.5, self.shooter)) + + # fire command + # TODO fix this code later + if self.opController.getRawAxis(2) >= 250: + FlyWheelSpeed(1, self.intake) + + else: + FlyWheelSpeed(0, self.intake) + + # climber + if ( + self.opController.getRawAxis(0) > 0.1 + or self.opController.getRawAxis(0) > -0.1 + ): + manualROT(self.opController.getRawAxis(0)) + + # Cancel all + self.opController.button(8).onTrue(commands2.InstantCommand(self.cancelAll)) def cancelAll(self) -> None: """ From dbd786d56ae6818ea5d5f361c4013f7e89e275ba Mon Sep 17 00:00:00 2001 From: kredcool Date: Sun, 10 Mar 2024 16:35:29 -0400 Subject: [PATCH 2/5] adding --- rio/commands/setIntakeSpeed.py | 3 ++- rio/robotcontainer.py | 47 +++++++++------------------------- 2 files changed, 14 insertions(+), 36 deletions(-) diff --git a/rio/commands/setIntakeSpeed.py b/rio/commands/setIntakeSpeed.py index 05015ba..f7c2140 100644 --- a/rio/commands/setIntakeSpeed.py +++ b/rio/commands/setIntakeSpeed.py @@ -29,7 +29,8 @@ def execute(self): def isFinished(self): return True - + def end(self, interrupted: bool): + self.intakeSubsystem.intake(False) logging.debug(f"Intake suck done") return True diff --git a/rio/robotcontainer.py b/rio/robotcontainer.py index d8628c9..7873864 100644 --- a/rio/robotcontainer.py +++ b/rio/robotcontainer.py @@ -97,6 +97,15 @@ def __init__(self) -> None: ) ) + self.shooter.setDefaultCommand( + commands2.cmd.run( + lambda: FlyWheelSpeed( + self.opController.getRawAxis(2) - 0.16, self.shooter + ), + self.shooter, + ) + ) + def configureButtonBindings(self) -> None: """ Use this method to define your button->command mappings. Buttons can be created by @@ -165,32 +174,6 @@ def configureButtonBindings(self) -> None: # Operator Commands # ============================== - """ - # moving intake - self.opController.pov(90).whileTrue(IntakeRotationMAN(1, self.intake)) # out - self.opController.pov(270).whileTrue(IntakeRotationMAN(-1, self.intake)) # in - - # moving shooter - self.opController.pov(0).whileTrue(manualROT(0.5, self.shooter)) - self.opController.pov(180).whileTrue(manualROT(-0.5, self.shooter)) - - self.driverController.pov(0).whileTrue(ShooterROT(60, self.shooter)) - - # PID shooter rotation (NOT CURRENTLY WORKING) - - # self.opController.pov(0).whileTrue(ShooterROT(0,self.shooter)) # out - # self.opController.pov(180).whileTrue(ShooterROT(40,self.shooter)) # out - - self.opController.b().whileTrue(RotateIntake(60, self.intake)) - - # Cancel all when x is pressed - self.opController.x().onTrue(commands2.InstantCommand(self.cancelAll)) - - self.opController.back().onTrue( - commands2.InstantCommand(self.intake.zeroIntake) - ) - """ - # intake keybinds # intake movement self.opController.button(2).whileTrue(IntakeRotationMAN(1, self.intake)) # out @@ -205,20 +188,14 @@ def configureButtonBindings(self) -> None: self.opController.button(3).whileTrue(manualROT(0.5, self.shooter)) self.opController.button(4).whileTrue(manualROT(-0.5, self.shooter)) - # fire command - # TODO fix this code later - if self.opController.getRawAxis(2) >= 250: - FlyWheelSpeed(1, self.intake) - - else: - FlyWheelSpeed(0, self.intake) - + """ # climber if ( self.opController.getRawAxis(0) > 0.1 or self.opController.getRawAxis(0) > -0.1 ): - manualROT(self.opController.getRawAxis(0)) + climb(self.opController.getRawAxis(0),self.climber) + """ # Cancel all self.opController.button(8).onTrue(commands2.InstantCommand(self.cancelAll)) From 543294299605d38cc027343ee92a2c0c929c6e31 Mon Sep 17 00:00:00 2001 From: NotSimon5673 Date: Sun, 10 Mar 2024 18:16:17 -0400 Subject: [PATCH 3/5] made changes --- rio/commands/resetYaw.py | 23 +++++++++++++++++++++++ rio/commands/setIntakeSpeed.py | 1 - rio/pyproject.toml | 2 +- rio/robotcontainer.py | 6 ++++++ rio/subsystems/drivesubsystem.py | 3 +++ 5 files changed, 33 insertions(+), 2 deletions(-) create mode 100644 rio/commands/resetYaw.py diff --git a/rio/commands/resetYaw.py b/rio/commands/resetYaw.py new file mode 100644 index 0000000..f2c1c45 --- /dev/null +++ b/rio/commands/resetYaw.py @@ -0,0 +1,23 @@ +import commands2 + +from subsystems.drivesubsystem import DriveSubsystem + + +class ResetYaw(commands2.Command): + + def __init__( + self, + _drivetrain=DriveSubsystem, + angle=0, + ): + super().__init__() + + # local subsystem instance + self.subsystem = _drivetrain + self.angle = angle + + def initialize(self): + self.subsystem.resetYaw(self.angle) + + def end(self, interrupted: bool): + return True diff --git a/rio/commands/setIntakeSpeed.py b/rio/commands/setIntakeSpeed.py index f7c2140..aca8600 100644 --- a/rio/commands/setIntakeSpeed.py +++ b/rio/commands/setIntakeSpeed.py @@ -31,6 +31,5 @@ def isFinished(self): return True def end(self, interrupted: bool): - self.intakeSubsystem.intake(False) logging.debug(f"Intake suck done") return True diff --git a/rio/pyproject.toml b/rio/pyproject.toml index 453fc4b..5e267cd 100644 --- a/rio/pyproject.toml +++ b/rio/pyproject.toml @@ -27,4 +27,4 @@ robotpy_extras = [ ] # Other pip packages to install -requires = [] +requires = [] \ No newline at end of file diff --git a/rio/robotcontainer.py b/rio/robotcontainer.py index 7873864..01e1917 100644 --- a/rio/robotcontainer.py +++ b/rio/robotcontainer.py @@ -35,6 +35,7 @@ from commands.intakeUntilNote import intakeUntilNote from commands.setIntakeSpeed import SetIntakeSpeed from commands.loadMagazine import LoadMagazine +from commands.resetYaw import ResetYaw # NetworkTables from ntcore import NetworkTableInstance @@ -169,6 +170,11 @@ def configureButtonBindings(self) -> None: FlyWheelSpeed(0, self.shooter), # stops the Flywheel ) ) + self.driverController.start().onTrue(ResetYaw(self.robotDrive)) + + self.driverController.back().onTrue( + commands2.InstantCommand(self.intake.zeroIntake) + ) # ============================== # Operator Commands diff --git a/rio/subsystems/drivesubsystem.py b/rio/subsystems/drivesubsystem.py index 9d7f794..2e1f4cf 100644 --- a/rio/subsystems/drivesubsystem.py +++ b/rio/subsystems/drivesubsystem.py @@ -301,3 +301,6 @@ def getTurnRate(self) -> float: :returns: The turn rate of the robot, in degrees per second """ return self.gyro.getRate() * (-1.0 if DriveConstants.kGyroReversed else 1.0) + + def resetYaw(self, angle) -> None: + self.gyro.setYaw(angle, 100) From 3f1896198236cfac35c97ba970a7a55326d66b9c Mon Sep 17 00:00:00 2001 From: kredcool Date: Mon, 11 Mar 2024 16:28:24 -0400 Subject: [PATCH 4/5] formatting --- rio/commands/resetYaw.py | 1 - rio/constants.py | 1 - 2 files changed, 2 deletions(-) diff --git a/rio/commands/resetYaw.py b/rio/commands/resetYaw.py index f2c1c45..efd8825 100644 --- a/rio/commands/resetYaw.py +++ b/rio/commands/resetYaw.py @@ -4,7 +4,6 @@ class ResetYaw(commands2.Command): - def __init__( self, _drivetrain=DriveSubsystem, diff --git a/rio/constants.py b/rio/constants.py index 38e04b6..90129fc 100644 --- a/rio/constants.py +++ b/rio/constants.py @@ -147,7 +147,6 @@ class AutoConstants: class SuperStrucConstants: - # angles for shooter ShootPos = 324 LoadPos = 208 From e839e101555f705f60b858552be4e90167bc6fbb Mon Sep 17 00:00:00 2001 From: kredcool Date: Tue, 12 Mar 2024 19:37:57 -0400 Subject: [PATCH 5/5] fixing dash error --- .github/workflows/dashboard-workflow.yml | 75 ------------------------ 1 file changed, 75 deletions(-) delete mode 100644 .github/workflows/dashboard-workflow.yml diff --git a/.github/workflows/dashboard-workflow.yml b/.github/workflows/dashboard-workflow.yml deleted file mode 100644 index 4b3604a..0000000 --- a/.github/workflows/dashboard-workflow.yml +++ /dev/null @@ -1,75 +0,0 @@ -name: Makefile CI - -on: - push: - branches: ["main"] - pull_request: - branches: ["main"] - -jobs: - make_dashboard: - name: Build Dashboard - runs-on: ubuntu-latest - steps: - - name: Setup Python - uses: actions/setup-python@v2 - with: - python-version: "3.10" - architecture: x64 - - - run: sudo apt update - - - run: sudo apt install curl - - - name: Install NPM - run: curl -o- https://raw.githubusercontent.com/nvm-sh/nvm/v0.39.7/install.sh | bash - - - name: Install npm deps - run: cd dashboard && npm ci - - - id: cache-pipenv - uses: actions/cache@v3 - with: - path: ~/.local/share/virtualenvs - key: ${{ runner.os }}-pipenv-${{ hashFiles('dashboard/Pipfile.lock') }} - - - name: Install dependencies - if: steps.cache-pipenv.outputs.cache-hit != 'true' - run: | - cd dashboard && pipenv install --deploy --dev - - - run: cd dashboard && pipenv run make stage - - - uses: actions/upload-artifact@v2 - with: - name: Dashboard_Transpiled - path: dashboard/dist - - publish: - # Only run on tags - if: github.event_name == 'push' && contains(github.ref, 'refs/tags/') - runs-on: ubuntu-latest - name: Publish - needs: [make_dashboard] - - steps: - - uses: actions/download-artifact@v2 - with: - name: Dashboard_Transpiled - path: Dashboard_Transpiled/ - - - uses: papeloto/action-zip@v1 - with: - files: Dashboard_Transpiled/ - dest: Dashboard_Transpiled.zip - - - name: Upload Dashboard to release - uses: svenstaro/upload-release-action@v2 - with: - repo_token: ${{ secrets.GITHUB_TOKEN }} - file: "*.zip" - tag: ${{ github.ref }} - overwrite: true - prerelease: true - body: "Tidal Force Robotics, Automated with github ci/cd." - file_glob: true