-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
* Added base shooter class * added motors configuration aswell as the set speed and rotation * imported shooter component to robot.py and made an injecting button in teleopperiodic * removed motor speeds feedback method * removed inject method and deployed variable * renamed variable voltsge_request to flywheel_request --------- Co-authored-by: Max Worrall <96847801+Tsunami014@users.noreply.github.com> Co-authored-by: clubpenguin <amber.knights@thedropbears.org.au> Co-authored-by: fotnitfpro000 <117606045+fotnitfpro000@users.noreply.github.com>
- Loading branch information
1 parent
aa36695
commit 45b50c7
Showing
3 changed files
with
65 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,51 @@ | ||
from magicbot import tunable | ||
from rev import CANSparkMax | ||
from ids import SparkMaxIds, TalonIds | ||
import phoenix6 | ||
from phoenix6.configs import ( | ||
config_groups, | ||
MotorOutputConfigs, | ||
) | ||
from phoenix6.controls import VoltageOut | ||
import phoenix6.hardware | ||
|
||
|
||
class Shooter: | ||
flywheel_speed = tunable(0.0) | ||
inject_speed = tunable(0.0) | ||
|
||
def __init__(self): | ||
self.top_flywheel = phoenix6.hardware.TalonFX(TalonIds.top_flywheel) | ||
self.bottom_flywheel = phoenix6.hardware.TalonFX(TalonIds.bottom_flywheel) | ||
self.inject_flywheel = CANSparkMax( | ||
SparkMaxIds.inject_flywheel, CANSparkMax.MotorType.kBrushless | ||
) | ||
|
||
# Configure bottom flywheel motor | ||
bottom_config = self.bottom_flywheel.configurator | ||
bottom_flywheel_config = MotorOutputConfigs() | ||
bottom_flywheel_config.inverted = config_groups.InvertedValue.CLOCKWISE_POSITIVE | ||
|
||
bottom_config.apply(bottom_flywheel_config) | ||
|
||
self.inject_flywheel.setInverted(True) | ||
|
||
self.should_inject = False | ||
|
||
def shoot(self): | ||
self.should_inject = True | ||
|
||
def is_ready(self): | ||
return True | ||
|
||
def execute(self): | ||
"""This gets called at the end of the control loop""" | ||
flywheel_request = VoltageOut(12.0 * self.flywheel_speed) | ||
if self.should_inject: | ||
self.inject_flywheel.set(self.inject_speed) | ||
else: | ||
self.inject_flywheel.set(0.0) | ||
|
||
self.top_flywheel.set_control(flywheel_request) | ||
self.bottom_flywheel.set_control(flywheel_request) | ||
self.should_inject = False |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters