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

Commit

Permalink
hazır gibi
Browse files Browse the repository at this point in the history
  • Loading branch information
MorphaxTheDeveloper committed Mar 13, 2024
1 parent 450ce0e commit 403f432
Show file tree
Hide file tree
Showing 6 changed files with 29 additions and 8 deletions.
8 changes: 5 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ public RobotContainer() {

swerveSubsystem.setDefaultCommand(new SwerveJoystickCmd(
swerveSubsystem,
() -> -driverJoytick.getRawAxis(OIConstants.kDriverYAxis),
() -> driverJoytick.getRawAxis(OIConstants.kDriverXAxis),
() -> driverJoytick.getRawAxis(OIConstants.kDriverYAxis),
() -> -driverJoytick.getRawAxis(OIConstants.kDriverXAxis),
() -> driverJoytick.getRawAxis(OIConstants.kDriverRotAxis),
() -> !driverJoytick.getRawButton(OIConstants.kDriverFieldOrientedButtonIdx)));

Expand All @@ -98,6 +98,8 @@ private void configureBindings() {

//buton 1
new JoystickButton(driverJoytick, 1).whileTrue(new InstantCommand(()-> m_feeder.forward()));
new JoystickButton(driverJoytick, 1).whileFalse(new InstantCommand(()-> m_feeder.stop()));


//buton 2
new JoystickButton(driverJoytick, 2).whileTrue(new InstantCommand(()-> m_feeder.backward()));
Expand Down Expand Up @@ -140,7 +142,7 @@ private void configureBindings() {
// new JoystickButton(subJoytick, 3).whileTrue(new ShooterSetDegree(m_shooter, ()->70.0));

//button 5 Amfi
// new JoystickButton(subJoytick, 3).whileTrue(new ShooterSetDegree(m_shooter, ()->70.0));
new JoystickButton(subJoytick, 5).whileTrue(new ShooterSetDegree(m_shooter, ()->180.0));



Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/common/fedleme.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ public fedleme(IntakeSubsystem m_intake, FeederSubsystem m_feeder, JoystickSubsy
new InstantCommand(()-> m_shooter.ShootertoFeederPos())
.andThen(new IntakeModeChange(m_joystick, 0))
.alongWith(new WaitCommand(1).andThen(new GetNote(m_intake)))
.alongWith(new FeederRunTillSwitch(m_feeder, false))
.alongWith(new FeederRunTillSwitch(m_feeder, false, m_intake))



Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,17 @@

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.FeederSubsystem;
import frc.robot.subsystems.IntakeSubsystem;

public class FeederRunTillSwitch extends Command {
FeederSubsystem m_feeder;
boolean dursunmu;
IntakeSubsystem m_intake;


public FeederRunTillSwitch(FeederSubsystem m_feeder, boolean dursunmu) {
public FeederRunTillSwitch(FeederSubsystem m_feeder, boolean dursunmu, IntakeSubsystem m_intake) {
this.m_feeder = m_feeder;
this.m_intake = m_intake;
}

// Called when the command is initially scheduled.
Expand All @@ -33,6 +36,7 @@ public void execute() {
}
else{
m_feeder.stop();
m_intake.StopNoteMotor();
m_feeder.varmifalse();

}}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/FeederSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ public void runtillswitch(){
feedmotor.set(-0.6);
}else{
feedmotor.set(0.0);

}
}

Expand Down
15 changes: 15 additions & 0 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,27 @@ public class IntakeSubsystem extends SubsystemBase {
public DigitalInput intakedetector1 = new DigitalInput(8);
public DigitalInput intakedetector2 = new DigitalInput(9);
public boolean tekcalisma = true;
public boolean digeride = false;

public IntakeSubsystem() {
intakeMotor.setIdleMode(IdleMode.kBrake);
IntakeEncoder = intakeMotor.getEncoder();
}

public void digeridetrue(){
digeride = true;

}

public void digeridefalse(){
digeride = false;

}

public boolean digeridedondur(){
return digeride;
}

public void brakemode() {
intakeMotor.setIdleMode(IdleMode.kBrake);

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/JoystickSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ public void periodic() {
break;

case 1:
intakedeger = 11.7;
intakedeger = 12.5;
break;
}

Expand All @@ -59,7 +59,7 @@ public void periodic() {
break;

case 2:
shooterdeger = 140;
shooterdeger = 164;
break;
}

Expand Down

0 comments on commit 403f432

Please sign in to comment.