-
Couldn't load subscription status.
- Fork 0
Shooter #4
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Open
ShmayaR
wants to merge
28
commits into
main
Choose a base branch
from
shooter
base: main
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Shooter #4
Changes from 11 commits
Commits
Show all changes
28 commits
Select commit
Hold shift + click to select a range
430e667
added constants commands and subsystem class
ShmayaR 4ffd554
added code to subsystem constants and command
ShmayaR 86e083b
Update RobotContainer.java
ShmayaR 232ad10
Update RobotContainer.java
ShmayaR a4b05aa
Update ShooterConstants.java
ShmayaR 0772e04
renamed variables in enum to match
ShmayaR 86b5917
Update ShooterConstants.java
ShmayaR 7b6a0e5
Update ShooterConstants.java
ShmayaR 8339018
renamed setTargetPercentageVoltageOutput to SetMotorOutput
ShmayaR 853f167
Update ShooterConstants.java
ShmayaR 36def3f
added function to subsystem for setting a state for the shooter
ShmayaR a32ac41
changed command form instant command to a start end command
ShmayaR d8e2605
Update Shooter.java
ShmayaR 0e72872
Update ShooterConstants.java
ShmayaR e5be1c2
removed INHALE_GAME_PIECE state
ShmayaR 5baaacb
changed name of setShooterState to shooterStateVoltagePercentage
ShmayaR d8220a8
Update ShooterCommands.java
ShmayaR fde22d2
Merge branch 'main' into shooter
ShmayaR 37900ed
Update Shooter.java
ShmayaR cdf7fcd
switched all the targetMotorOutputPercentage to targetVoltagePercentage
ShmayaR 9037e62
Update RobotContainer.java
ShmayaR f8d1e26
Update Shooter.java
ShmayaR 2450b98
Update Shooter.java
ShmayaR 69c361b
Update Shooter.java
ShmayaR 3b3b4a6
Update Robot.java
ShmayaR 83e27f0
Update RobotContainer.java
ShmayaR ecdcd49
Update Robot.java
ShmayaR aa000ef
Update ShooterConstants.java
ShmayaR File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or 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 hidden or 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,28 @@ | ||
| package frc.robot.subsystems.Shooter; | ||
|
|
||
|
|
||
| import com.ctre.phoenix.motorcontrol.ControlMode; | ||
| import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; | ||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||
|
|
||
| public class Shooter extends SubsystemBase { | ||
| private final WPI_TalonSRX rightMotor = ShooterConstants.RIGHT_MOTOR; | ||
| private final WPI_TalonSRX leftMotor = ShooterConstants.LEFT_MOTOR; | ||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| private ShooterConstants.ShooterState currentState; | ||
|
|
||
| void stopMotors() { | ||
| setMotorOutput(0); | ||
| } | ||
|
|
||
| void setTargetState(ShooterConstants.ShooterState targetState) { | ||
| setMotorOutput(targetState.setShooterState); | ||
| currentState = targetState; | ||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| } | ||
|
|
||
| void setMotorOutput(double percentageMotorOutput) { | ||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| rightMotor.set(ControlMode.PercentOutput, percentageMotorOutput); | ||
| leftMotor.set(ControlMode.PercentOutput, percentageMotorOutput); | ||
| } | ||
| } | ||
|
|
||
|
|
||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
23 changes: 23 additions & 0 deletions
23
src/main/java/frc/robot/subsystems/Shooter/ShooterCommands.java
This file contains hidden or 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,23 @@ | ||
| package frc.robot.subsystems.Shooter; | ||
|
|
||
| import edu.wpi.first.wpilibj2.command.Command; | ||
| import edu.wpi.first.wpilibj2.command.InstantCommand; | ||
| import edu.wpi.first.wpilibj2.command.StartEndCommand; | ||
| import frc.robot.RobotContainer; | ||
|
|
||
| public class ShooterCommands { | ||
| public static Command getSetTargetStateCommand(ShooterConstants.ShooterState targetState) { | ||
| return new InstantCommand( | ||
| () -> RobotContainer.SHOOTER.setTargetState(targetState) | ||
| ); | ||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| } | ||
|
|
||
| private static Command getSetMotorOutputCommand(double motorOutput) { | ||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| return new StartEndCommand( | ||
| () -> RobotContainer.SHOOTER.setMotorOutput(motorOutput), | ||
| RobotContainer.SHOOTER::stopMotors, | ||
| RobotContainer.SHOOTER | ||
| ); | ||
| } | ||
| } | ||
|
|
||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
58 changes: 58 additions & 0 deletions
58
src/main/java/frc/robot/subsystems/Shooter/ShooterConstants.java
This file contains hidden or 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,58 @@ | ||
| package frc.robot.subsystems.Shooter; | ||
|
|
||
| import com.ctre.phoenix.motorcontrol.InvertType; | ||
| import com.ctre.phoenix.motorcontrol.NeutralMode; | ||
| import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; | ||
|
|
||
| public class ShooterConstants { | ||
| private static final int | ||
| RIGHT_MOTOR_ID = 3, | ||
| LEFT_MOTOR_ID = 4; | ||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
|
||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| static final WPI_TalonSRX | ||
| RIGHT_MOTOR = new WPI_TalonSRX(RIGHT_MOTOR_ID), | ||
| LEFT_MOTOR = new WPI_TalonSRX(LEFT_MOTOR_ID); | ||
|
|
||
| private static final InvertType RIGHT_MOTOR_INVERTED_VALUE = InvertType.None; | ||
| private static final InvertType LEFT_MOTOR_INVERTED_VALUE = InvertType.InvertMotorOutput; | ||
| private static final NeutralMode NEUTRAL_MODE = NeutralMode.Coast; | ||
| private static final double VOLTAGE_COMPENSATION_SATURATION = 12; | ||
|
|
||
| static { | ||
| configureRightMotor(); | ||
| configureLeftMotor(); | ||
| } | ||
|
|
||
| private static final void configureRightMotor() { | ||
| RIGHT_MOTOR.configFactoryDefault(); | ||
|
|
||
| RIGHT_MOTOR.setInverted(RIGHT_MOTOR_INVERTED_VALUE); | ||
| RIGHT_MOTOR.setNeutralMode(NEUTRAL_MODE); | ||
|
|
||
| RIGHT_MOTOR.enableVoltageCompensation(true); | ||
| RIGHT_MOTOR.configVoltageCompSaturation(VOLTAGE_COMPENSATION_SATURATION); | ||
| } | ||
|
|
||
| private static final void configureLeftMotor() { | ||
| LEFT_MOTOR.configFactoryDefault(); | ||
|
|
||
| LEFT_MOTOR.setInverted(LEFT_MOTOR_INVERTED_VALUE); | ||
| LEFT_MOTOR.setNeutralMode(NEUTRAL_MODE); | ||
|
|
||
| LEFT_MOTOR.enableVoltageCompensation(true); | ||
| LEFT_MOTOR.configVoltageCompSaturation(VOLTAGE_COMPENSATION_SATURATION); | ||
| } | ||
|
|
||
| public enum ShooterState { | ||
| SHOOT(1), | ||
| EJECT(0.3), | ||
| COLLECT(-0.3), | ||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| STOP(0); | ||
|
|
||
| final double setShooterState; | ||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
|
||
| ShooterState(double setShooterState) { | ||
| this.setShooterState = setShooterState; | ||
| } | ||
ShmayaR marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| } | ||
| } | ||
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
Uh oh!
There was an error while loading. Please reload this page.