-
Notifications
You must be signed in to change notification settings - Fork 0
Azoulay #9
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
azdaniel123
wants to merge
19
commits into
main
Choose a base branch
from
side-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
Azoulay #9
Changes from 5 commits
Commits
Show all changes
19 commits
Select commit
Hold shift + click to select a range
5e0694a
90% of the constans
azdaniel123 393d100
make side shooter constans
azdaniel123 5fbe4a6
control+alt+L
azdaniel123 fba1a7f
rename
azdaniel123 da85522
false
azdaniel123 35f9790
stopid think
azdaniel123 9eebd78
תעשו את זה כאן
azdaniel123 8bb0443
sent all the problams
azdaniel123 dfb0223
הוספתי פידפור
azdaniel123 9d1f535
העברתי תקייה
azdaniel123 c36928f
last constans revyu
azdaniel123 6ae9dc7
final
azdaniel123 e46b8e1
#$%^&^%$%^&*&^%$#$%^&*&^%$%^&*&^%
azdaniel123 8b2c101
שם שנועד לעשות לישי בושות מול פיירפלייי
azdaniel123 f427577
fix
azdaniel123 1835e45
Update SideShooter.java
azdaniel123 86e06bb
for ezra
azdaniel123 c39f5d4
give me the next think alredy
azdaniel123 65b6243
hope that the last
azdaniel123 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
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,89 @@ | ||
| package SideShooter; | ||
|
|
||
| import com.ctre.phoenix6.configs.CANcoderConfiguration; | ||
| import com.ctre.phoenix6.configs.TalonFXConfiguration; | ||
| import com.ctre.phoenix6.hardware.CANcoder; | ||
| import com.ctre.phoenix6.hardware.TalonFX; | ||
| import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue; | ||
| import com.ctre.phoenix6.signals.InvertedValue; | ||
| import com.ctre.phoenix6.signals.NeutralModeValue; | ||
| import com.ctre.phoenix6.signals.SensorDirectionValue; | ||
| import com.revrobotics.CANSparkMax; | ||
| import com.revrobotics.CANSparkMaxLowLevel; | ||
| import edu.wpi.first.math.controller.PIDController; | ||
| import edu.wpi.first.math.geometry.Rotation2d; | ||
| import edu.wpi.first.math.trajectory.TrapezoidProfile; | ||
|
|
||
| public class SideShooterConstants { | ||
| private static final int SHOOTING_MOTOR_ID = 0; | ||
| private static final int ANGLE_MOTOR_ID = 0; | ||
| private static final int ENCODER_ID = 0; | ||
| private static final double ANGLE_MAGNET_OFFSET = 0; | ||
| private static final CANSparkMax.IdleMode ANGLE_MOTOR_IDLE_MODE = CANSparkMax.IdleMode.kBrake; | ||
| private static final AbsoluteSensorRangeValue ANGEL_ENCODER_VALUE = AbsoluteSensorRangeValue.Signed_PlusMinusHalf; | ||
azdaniel123 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| private static final SensorDirectionValue ANGLE_ENCODER_SENSOR_DIRECTION = SensorDirectionValue.CounterClockwise_Positive; | ||
| private static final InvertedValue SHOOTER_INVERTED_VALUE = InvertedValue.CounterClockwise_Positive; | ||
| private static final NeutralModeValue SHOOTING_NEUTRAL_MODE_VALUE = NeutralModeValue.Brake; | ||
azdaniel123 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| private static final double VOLTAGE_COMPENSATION_SATURATION = 16.45; | ||
| private static final boolean ANGLE_MOTOR_INVERTED = false; | ||
| static final TalonFX SHOOTING_MOTOR = new TalonFX(SHOOTING_MOTOR_ID); | ||
| static final CANSparkMax ANGLE_MOTOR = new CANSparkMax(ANGLE_MOTOR_ID, CANSparkMaxLowLevel.MotorType.kBrushless); | ||
| private static final CANcoder ANGLE_ENCODER = new CANcoder(ENCODER_ID); | ||
|
|
||
| private static final double | ||
| MAX_ANGEL_VELOCITY = 600, | ||
| MAX_ANGEL_ACCELERATION = 500; | ||
| static final TrapezoidProfile.Constraints ANGLE_Constraints = new TrapezoidProfile.Constraints( | ||
| MAX_ANGEL_VELOCITY, MAX_ANGEL_ACCELERATION | ||
azdaniel123 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| ); | ||
|
|
||
| private static final int | ||
azdaniel123 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
azdaniel123 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| ANGLE_MOTOR_P = 0, | ||
| ANGLE_MOTOR_I = 0, | ||
| ANGLE_MOTOR_D = 0; | ||
|
|
||
| static final PIDController ANGLE_PID_CONTROLLER = new PIDController(ANGLE_MOTOR_P, ANGLE_MOTOR_I, ANGLE_MOTOR_D); | ||
|
|
||
azdaniel123 marked this conversation as resolved.
Show resolved
Hide resolved
azdaniel123 marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| static { | ||
| configureAngleEncoder(); | ||
| configureAngleMotor(); | ||
| configureShootingMotor(); | ||
| } | ||
|
|
||
| private static void configureShootingMotor() { | ||
| TalonFXConfiguration config = new TalonFXConfiguration(); | ||
| config.Audio.BeepOnBoot = false; | ||
azdaniel123 marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| config.MotorOutput.Inverted = SHOOTER_INVERTED_VALUE; | ||
| config.MotorOutput.NeutralMode = SHOOTING_NEUTRAL_MODE_VALUE; | ||
| config.Audio.BeepOnConfig = false; | ||
| SHOOTING_MOTOR.getConfigurator().apply(config); | ||
| } | ||
|
|
||
| private static void configureAngleMotor() { | ||
| ANGLE_MOTOR.restoreFactoryDefaults(); | ||
| ANGLE_MOTOR.setInverted(ANGLE_MOTOR_INVERTED); | ||
| ANGLE_MOTOR.setIdleMode(ANGLE_MOTOR_IDLE_MODE); | ||
| ANGLE_MOTOR.enableVoltageCompensation(VOLTAGE_COMPENSATION_SATURATION); | ||
| } | ||
|
|
||
| private static void configureAngleEncoder() { | ||
| CANcoderConfiguration configureAngleMotor = new CANcoderConfiguration(); | ||
| configureAngleMotor.MagnetSensor.AbsoluteSensorRange = ANGEL_ENCODER_VALUE; | ||
| configureAngleMotor.MagnetSensor.MagnetOffset = ANGLE_MAGNET_OFFSET; | ||
| configureAngleMotor.MagnetSensor.SensorDirection = ANGLE_ENCODER_SENSOR_DIRECTION; | ||
| ANGLE_ENCODER.getConfigurator().apply(configureAngleMotor); | ||
| } | ||
|
|
||
| public enum SideShooterState { | ||
| COLLECT_POSITION(Rotation2d.fromDegrees(0)), | ||
| MID_LEVEL_POSITION(Rotation2d.fromDegrees(222)), | ||
| HIGH_LEVEL_POSITION(Rotation2d.fromDegrees(666.3)); | ||
| private Rotation2d angel; | ||
azdaniel123 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
azdaniel123 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
|
||
| SideShooterState(Rotation2d angel) { | ||
| this.angel = angel; | ||
azdaniel123 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
|
||
|
|
||
azdaniel123 marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| } | ||
| } | ||
azdaniel123 marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| } | ||
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.