Skip to content
This repository has been archived by the owner on Nov 10, 2024. It is now read-only.

Commit

Permalink
2 kazık anlamayana cok yazık XDxxDxdD
Browse files Browse the repository at this point in the history
  • Loading branch information
MorphaxTheDeveloper committed Mar 8, 2024
1 parent c04ba7f commit e7f5906
Show file tree
Hide file tree
Showing 5 changed files with 72 additions and 35 deletions.
88 changes: 64 additions & 24 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ public class RobotContainer {
private final ShooterSubsystem m_shooter = new ShooterSubsystem();
private final SwerveSubsystem swerveSubsystem = new SwerveSubsystem();
private final XboxController driverJoytick = new XboxController(1);
private final XboxController subJoytick = new XboxController(3);
private final FeederSubsystem m_feeder = new FeederSubsystem();

public RobotContainer() {
Expand All @@ -60,8 +61,48 @@ public RobotContainer() {
}

private void configureBindings() {
//Driver
new JoystickButton(driverJoytick, 8).whileTrue(new InstantCommand(() -> swerveSubsystem.zeroHeading()));

new JoystickButton(driverJoytick, 6).whileTrue(new RunTillSwitch(m_intake,false));

new JoystickButton(driverJoytick, 6).whileFalse(new InstantCommand(()->m_intake.StopNoteMotor()));

new JoystickButton(driverJoytick, 5).whileTrue(new InstantCommand(() -> m_feeder.backward()));
new JoystickButton(driverJoytick, 5).whileFalse(new InstantCommand(() -> m_feeder.stop()));




//sub
new JoystickButton(subJoytick, 1).whileTrue(new dalhacan(m_intake, m_shooter));

new JoystickButton(subJoytick, 6).whileTrue(new FeederRunTillSwitch(m_feeder, false));
new JoystickButton(subJoytick, 6).whileFalse(new InstantCommand(() -> m_feeder.stop()));

new JoystickButton(subJoytick, 2).whileTrue(new PidIntakeCommand(m_intake,1.3));

//once new JoystickButton(subJoytick, 2).whileTrue(new PidIntakeCommand(m_intake,1.3));

//sonra

new JoystickButton(subJoytick, 5).whileTrue(new InstantCommand(()->m_intake.getNote()));
new JoystickButton(subJoytick, 5).whileFalse(new InstantCommand(()->m_intake.StopNoteMotor()));

new JoystickButton(subJoytick, 3).whileTrue(new ShooterSetDegree(m_shooter, 70.0));

new JoystickButton(subJoytick, 4)
.whileTrue(new InstantCommand(() -> m_shooter.ShooterThrowMotorOutput(0.8)));

new JoystickButton(subJoytick, 4)
.whileFalse(new InstantCommand(() -> m_shooter.ShooterThrowAllMotorStop()));

new JoystickButton(subJoytick, 7).whileTrue(new InstantCommand(() -> m_intake.reset()));





new JoystickButton(driverJoytick, 7).whileTrue(new InstantCommand(() -> swerveSubsystem.zeroHeading()));
// new JoystickButton(driverJoytick, 3).whileTrue(new PidIntakeCommand(m_intake,
// 20));
// new JoystickButton(driverJoytick, 3).whileFalse(new InstantCommand(() ->
Expand All @@ -72,23 +113,23 @@ private void configureBindings() {
// m_shooter.AngleEncoderReset()));
// new JoystickButton(driverJoytick, 6).whileTrue(new InstantCommand(()->
// m_feeder.backward()));
new JoystickButton(driverJoytick, 10)
.whileTrue(new InstantCommand(() -> m_shooter.ShooterThrowMotorOutput(0.8)));

new JoystickButton(driverJoytick, 10)
.whileFalse(new InstantCommand(() -> m_shooter.ShooterThrowAllMotorStop()));
// new JoystickButton(driverJoytick, 10)
// .whileTrue(new InstantCommand(() -> m_shooter.ShooterThrowMotorOutput(0.8)));

// new JoystickButton(driverJoytick, 10)
// .whileFalse(new InstantCommand(() -> m_shooter.ShooterThrowAllMotorStop()));

new JoystickButton(driverJoytick, 1).whileTrue(new dalhacan(m_intake, m_shooter));
new JoystickButton(driverJoytick, 1).whileTrue(new InstantCommand(() -> m_intake.degistirmee()));
new JoystickButton(driverJoytick, 3).whileTrue(new ShooterSetDegree(m_shooter, 160.0));
// new JoystickButton(driverJoytick, 4).whileTrue(new cinarcan(m_intake,
// m_feeder));
new JoystickButton(driverJoytick, 4).whileTrue(new RunTillSwitch(m_intake,false));
new JoystickButton(driverJoytick, 4).whileFalse(new InstantCommand(() -> m_intake.StopNoteMotor()));
// new JoystickButton(driverJoytick, 1).whileTrue(new InstantCommand(() -> m_intake.degistirmee()));
// new JoystickButton(driverJoytick, 3).whileTrue(new ShooterSetDegree(m_shooter, 160.0));
// // new JoystickButton(driverJoytick, 4).whileTrue(new cinarcan(m_intake,
// // m_feeder));
// new JoystickButton(driverJoytick, 4).whileTrue(new RunTillSwitch(m_intake,false));
// new JoystickButton(driverJoytick, 4).whileFalse(new InstantCommand(() -> m_intake.StopNoteMotor()));

new JoystickButton(driverJoytick, 1).whileFalse(new InstantCommand(() -> m_intake.StopAngleMotor()));
new JoystickButton(driverJoytick, 2).whileTrue(new InstantCommand(() -> m_intake.reset()));
new JoystickButton(driverJoytick, 2).whileTrue(new InstantCommand(() -> m_shooter.AngleEncoderReset()));
// new JoystickButton(driverJoytick, 1).whileFalse(new InstantCommand(() -> m_intake.StopAngleMotor()));
// new JoystickButton(driverJoytick, 2).whileTrue(new InstantCommand(() -> m_intake.reset()));
// new JoystickButton(driverJoytick, 2).whileTrue(new InstantCommand(() -> m_shooter.AngleEncoderReset()));

// new JoystickButton(driverJoytick, 1).whileTrue(new
// InstantCommand(()->m_shooter.AngleEncoderReset()));
Expand All @@ -113,20 +154,19 @@ private void configureBindings() {
// new JoystickButton(driverJoytick, 4).whileFalse(new RunCommand(()-> m_feeder.stop()));
// new JoystickButton(driverJoytick, 9).whileTrue(new cinarcan(m_intake, m_feeder));
//new JoystickButton(driverJoytick, 9).whileFalse(new cinarcan(m_intake, m_feeder));
new JoystickButton(driverJoytick, 5).whileTrue(new RunTillSwitch(m_intake,false));
new JoystickButton(driverJoytick, 5).whileFalse(new InstantCommand(()->m_intake.StopNoteMotor()));
// new JoystickButton(driverJoytick, 5).whileTrue(new RunTillSwitch(m_intake,false));
// new JoystickButton(driverJoytick, 5).whileFalse(new InstantCommand(()->m_intake.StopNoteMotor()));


// new JoystickButton(driverJoytick, 5).onTrue(new InstantCommand(()-> m_intake.degistir()));

new JoystickButton(driverJoytick, 6).whileTrue(new FeederRunTillSwitch(m_feeder, false));
new JoystickButton(driverJoytick, 6).whileFalse(new InstantCommand(() -> m_feeder.stop()));
// new JoystickButton(driverJoytick, 6).whileTrue(new FeederRunTillSwitch(m_feeder, false));
// new JoystickButton(driverJoytick, 6).whileFalse(new InstantCommand(() -> m_feeder.stop()));

new JoystickButton(driverJoytick, 8).whileTrue(new InstantCommand(() -> m_intake.runpickupmotor(0.8)));
new JoystickButton(driverJoytick, 8).whileFalse(new InstantCommand(() -> m_intake.runpickupmotor(0)));
//new JoystickButton(driverJoytick, 9).whileTrue(new InstantCommand(() -> m_feeder.backward()));
new JoystickButton(driverJoytick, 9).whileFalse(new InstantCommand(() -> m_feeder.stop()));
new JoystickButton(driverJoytick, 9).whileFalse(new InstantCommand(() -> m_intake.getNote()));
// new JoystickButton(driverJoytick, 8).whileTrue(new InstantCommand(() -> m_intake.runpickupmotor(0.8)));
// new JoystickButton(driverJoytick, 8).whileFalse(new InstantCommand(() -> m_intake.runpickupmotor(0)));

// new JoystickButton(driverJoytick, 9).whileFalse(new InstantCommand(() -> m_intake.getNote()));


}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,6 @@ else if (position < -m_intake.getRawEncoderOutput()) {

@Override
public boolean isFinished() {
return getController().atSetpoint();
return false;
}
}
7 changes: 2 additions & 5 deletions src/main/java/frc/robot/commands/common/fedleme.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,12 @@
import frc.robot.subsystems.FeederSubsystem;
import frc.robot.subsystems.IntakeSubsystem;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
public class fedleme extends SequentialCommandGroup {
/** Creates a new fedleme. */
public fedleme(IntakeSubsystem m_intake, FeederSubsystem m_feeder) {
// Add your commands in the addCommands() call, e.g.
// addCommands(new FooCommand(), new BarCommand());

addCommands(

new PidIntakeCommand(m_intake, 1.8)

.andThen(new RunCommand(()-> m_intake.getNote())
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/FeederSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,11 @@ public void forward() {
}

public void backward2() {
feedmotor.set(-0.36);
feedmotor.set(-0.5);
}

public void backward() {
feedmotor.set(-0.8);
feedmotor.set(-0.6);
}

public void runtillswitch(){
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@

public class IntakeSubsystem extends SubsystemBase {
// intake nota motorları
public static WPI_VictorSPX intakeMotor1 = new WPI_VictorSPX(12);
public static CANSparkMax intakeMotor1 = new CANSparkMax(12,MotorType.kBrushed);
// intake main motor
public static CANSparkMax intakeMotor = new CANSparkMax(Constants.ports.intake_motor_angle, MotorType.kBrushless);

public RelativeEncoder IntakeEncoder;
public DigitalInput intakedetector1 = new DigitalInput(8);
public DigitalInput intakedetector2 = new DigitalInput(9);
Expand Down Expand Up @@ -52,7 +52,7 @@ public void NewIntakeMotorOutput(double value) {
}

public void getNote() {
intakeMotor1.set(0.4);
intakeMotor1.set(0.6);
}

public void degistir() {
Expand Down

0 comments on commit e7f5906

Please sign in to comment.