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

Commit

Permalink
nerdeyse bitti gib
Browse files Browse the repository at this point in the history
  • Loading branch information
MorphaxTheDeveloper committed Mar 12, 2024
1 parent 5c9b1e3 commit 96cfe46
Show file tree
Hide file tree
Showing 8 changed files with 133 additions and 47 deletions.
83 changes: 75 additions & 8 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
import frc.robot.commands.common.IntakeInputPosition;
import frc.robot.commands.common.dalhacan;
import frc.robot.commands.common.fedleme;
import frc.robot.commands.common.pickup;
import frc.robot.commands.feeder.FeederRunTillSwitch;
import frc.robot.subsystems.FeederSubsystem;
import frc.robot.subsystems.IntakeSubsystem;
Expand All @@ -60,7 +61,7 @@

public class RobotContainer {
private final IntakeSubsystem m_intake = new IntakeSubsystem();
// private final ShooterSubsystem m_shooter = new ShooterSubsystem();
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);
Expand All @@ -76,8 +77,8 @@ public RobotContainer() {
() -> !driverJoytick.getRawButton(OIConstants.kDriverFieldOrientedButtonIdx)));


//m_intake.setDefaultCommand(new PidIntakeCommand(m_intake,() -> m_joystick.getintakevalue()));
// m_shooter.setDefaultCommand(new ShooterSetDegree(m_shooter, () -> m_joystick.getshootervalue()));
m_intake.setDefaultCommand(new PidIntakeCommand(m_intake,() -> m_joystick.getintakevalue()));
//m_shooter.setDefaultCommand(new ShooterSetDegree(m_shooter, () -> m_joystick.getshootervalue()));



Expand All @@ -86,15 +87,79 @@ public RobotContainer() {
}

private void configureBindings() {
/*
____ ____ __ _ _ ____ ____
( \( _ \( )/ )( \( __)( _ \
) D ( ) / )( \ \/ / ) _) ) /
(____/(__\_)(__) \__/ (____)(__\_) */





new JoystickButton(driverJoytick, 1).whileTrue(new InstantCommand(()-> m_feeder.forward()));
new JoystickButton(driverJoytick, 2).whileTrue(new InstantCommand(()-> m_feeder.backward()));
// TIRMANMA new JoystickButton(driverJoytick, 1).whileTrue(new InstantCommand(()-> m_feeder.forward()));


/*
____ _ _ ____ ____ ____ __ _ _ ____ ____
/ ___)/ )( \( _ \( \( _ \( )/ )( \( __)( _ \
\___ \) \/ ( ) _ ( ) D ( ) / )( \ \/ / ) _) ) /
(____/\____/(____/(____/(__\_)(__) \__/ (____)(__\_)
*/





new JoystickButton(subJoytick, 2).whileTrue(new pickup(m_intake, m_joystick));
new JoystickButton(subJoytick, 2).whileTrue(new fedleme(m_intake, m_feeder, m_joystick,m_shooter));















//SUBDRIVER









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

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


// new JoystickButton(driverJoytick, 5).whileTrue(new RunTillSwitch(m_intake,false,m_feeder,m_joystick,m_shooter));
new JoystickButton(driverJoytick, 5).whileFalse(new InstantCommand(()->m_intake.StopNoteMotor()));
// new JoystickButton(driverJoytick, 7).whileTrue(new InstantCommand(()-> m_joystick.shootermodchange(0)));
//new JoystickButton(driverJoytick, 8).whileTrue(new InstantCommand(()-> m_joystick.shootermodchange(1)));

new JoystickButton(subJoytick, 4).whileTrue(new fedleme(m_intake, m_feeder, m_joystick,m_shooter));
new JoystickButton(driverJoytick, 4).whileTrue(new InstantCommand(()->m_feeder.varmitrue()));
new JoystickButton(driverJoytick, 4).whileFalse(new InstantCommand(()->m_feeder.stop()));
new JoystickButton(driverJoytick, 4).whileFalse(new InstantCommand(()->m_intake.StopNoteMotor()));



new JoystickButton(driverJoytick, 1).whileTrue(new InstantCommand(()-> m_joystick.intakemodchange(1)));
// new JoystickButton(driverJoytick, 5).whileTrue(new RunTillSwitch(m_intake,false,m_feeder,m_joystick,m_shooter));
//new JoystickButton(driverJoytick, 5).whileFalse(new InstantCommand(()->m_intake.StopNoteMotor()));
// new JoystickButton(subJoytick, 3).whileTrue(new ShooterSetDegree(m_shooter, ()->70.0));

// new JoystickButton(driverJoytick, 6).whileTrue(new FedX(m_intake, m_feeder, m_joystick,m_shooter));
Expand All @@ -117,7 +182,8 @@ private void configureBindings() {
new JoystickButton(subJoytick, 1).whileTrue(new InstantCommand(()->m_joystick.intakemodchange(1)));

// new JoystickButton(subJoytick, 6).whileTrue(new fedleme(m_intake, m_feeder, m_joystick,m_shooter));
new JoystickButton(subJoytick, 6).whileFalse(new InstantCommand(()->m_intake.StopNoteMotor()));

new JoystickButton(subJoytick, 6).whileFalse(new InstantCommand(()->m_intake.StopNoteMotor()));
new JoystickButton(subJoytick, 6).whileFalse(new InstantCommand(()->m_feeder.stop()));

//new JoystickButton(subJoytick, 6).whileTrue(new FeederRunTillSwitch(m_feeder, false));
Expand All @@ -142,6 +208,7 @@ private void configureBindings() {
// .whileFalse(new InstantCommand(() -> m_shooter.ShooterThrowAllMotorStop()));

new JoystickButton(subJoytick, 7).whileTrue(new InstantCommand(() -> m_intake.reset()));
// new JoystickButton(driverJoytick, 4).whileTrue(new InstantCommand(()->m_shooter.ShootertoFeederPos()));

// new JoystickButton(driverJoytick, 3).whileTrue(new PidIntakeCommand(m_intake,
// 20));
Expand All @@ -164,7 +231,7 @@ private void configureBindings() {
// 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).whileTrue(new RunTillSwitch(m_intake));
// new JoystickButton(driverJoytick, 4).whileFalse(new InstantCommand(() -> m_intake.StopNoteMotor()));

// new JoystickButton(driverJoytick, 1).whileFalse(new InstantCommand(() -> m_intake.StopAngleMotor()));
Expand Down
7 changes: 1 addition & 6 deletions src/main/java/frc/robot/commands/Intake/RunTillSwitch.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,12 +22,9 @@ public class RunTillSwitch extends Command {
boolean varmi = false;


public RunTillSwitch(IntakeSubsystem m_intake, boolean dursunmu,FeederSubsystem m_feeder,JoystickSubsystem m_joystick, ShooterSubsystem m_shooter) {
public RunTillSwitch(IntakeSubsystem m_intake, boolean dursunmu) {

this.m_intake = m_intake;
this.m_feeder = m_feeder;
this.m_joystick = m_joystick;
this.m_shooter = m_shooter;
}

// Called when the command is initially scheduled.
Expand Down Expand Up @@ -60,8 +57,6 @@ public void execute() {

m_intake.StopNoteMotor();
varmi = true;
new fedleme(m_intake, m_feeder, m_joystick, m_shooter);

}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ public ShooterSetDegree(ShooterSubsystem m_shooter, DoubleSupplier angle) {
super(

new PIDController(0.04,
0.01,
0.03,
Constants.values.shooter.PidShooterAngleKD),
() -> m_shooter.getMappedOutput(),
() -> angle.getAsDouble(),
Expand Down
22 changes: 22 additions & 0 deletions src/main/java/frc/robot/commands/common/pickup.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands.common;

import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.robot.commands.Intake.IntakeModeChange;
import frc.robot.commands.Intake.RunTillSwitch;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.subsystems.JoystickSubsystem;

// 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 pickup extends SequentialCommandGroup {
/** Creates a new pickup. */
public pickup(IntakeSubsystem m_intake, JoystickSubsystem m_joystick) {
addCommands(new RunTillSwitch(m_intake,false).alongWith(new IntakeModeChange(m_joystick, 1)));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ public void execute() {

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}
public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
Expand Down
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/subsystems/FeederSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,10 @@ public void backward() {
feedmotor.set(-0.9);
}

public void forward() {
feedmotor.set(0.9);
}

public void runtillswitch(){
if(detector.get()){
feedmotor.set(-0.6);
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/JoystickSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ public void periodic() {

switch (shootermod){
case 0:
shooterdeger = 0;
shooterdeger = -2.0;
break;

case 1:
Expand Down
58 changes: 28 additions & 30 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@

public class ShooterSubsystem extends SubsystemBase {

//public static CANSparkMax ShooterAngleMotor = new CANSparkMax(Constants.ports.shooter_motor_3, MotorType.kBrushless);
//public static CANSparkMax ShooterThrowMotor1 = new CANSparkMax(Constants.ports.shooter_motor_1, MotorType.kBrushless);
//public static CANSparkMax ShooterThrowMotor2 = new CANSparkMax(Constants.ports.shooter_motor_2, MotorType.kBrushless);
public static CANSparkMax ShooterAngleMotor = new CANSparkMax(Constants.ports.shooter_motor_3, MotorType.kBrushless);
public static CANSparkMax ShooterThrowMotor1 = new CANSparkMax(Constants.ports.shooter_motor_1, MotorType.kBrushless);
public static CANSparkMax ShooterThrowMotor2 = new CANSparkMax(Constants.ports.shooter_motor_2, MotorType.kBrushless);

public RelativeEncoder ShooterThrow1Encoder;
public RelativeEncoder ShooterThrow2Encoder;
Expand All @@ -27,12 +27,12 @@ public void setencodervalue(double value) {
}

public ShooterSubsystem() {
/* ShooterAngleMotor.setIdleMode(IdleMode.kBrake);
ShooterAngleMotor.setIdleMode(IdleMode.kBrake);
ShooterAngleEncoder = ShooterAngleMotor.getEncoder();
ShooterThrow1Encoder = ShooterThrowMotor1.getEncoder();
ShooterThrow2Encoder = ShooterThrowMotor2.getEncoder();
ShooterAngleMotor.setOpenLoopRampRate(Constants.values.shooter.AngleMotorOpenLoopRampRate);
setencodervalue(0.525);*/
setencodervalue(1.0);

}

Expand All @@ -41,31 +41,31 @@ public boolean getshooterswitchvalue() {
}

public void brakemode1() {
// ShooterThrowMotor1.setIdleMode(IdleMode.kBrake);
ShooterThrowMotor1.setIdleMode(IdleMode.kBrake);

}

public void brakemode2() {
// ShooterThrowMotor2.setIdleMode(IdleMode.kBrake);
ShooterThrowMotor2.setIdleMode(IdleMode.kBrake);

}

public void coastmode1() {
// ShooterThrowMotor1.setIdleMode(IdleMode.kCoast);
ShooterThrowMotor1.setIdleMode(IdleMode.kCoast);
}

public void coastmode2() {
//ShooterThrowMotor1.setIdleMode(IdleMode.kCoast);
ShooterThrowMotor1.setIdleMode(IdleMode.kCoast);
}

public void barkeall() {
// ShooterThrowMotor1.setIdleMode(IdleMode.kBrake);
//ShooterThrowMotor2.setIdleMode(IdleMode.kBrake);
ShooterThrowMotor1.setIdleMode(IdleMode.kBrake);
ShooterThrowMotor2.setIdleMode(IdleMode.kBrake);
}

public void coastall() {
// ShooterThrowMotor1.setIdleMode(IdleMode.kCoast);
// ShooterThrowMotor2.setIdleMode(IdleMode.kCoast);
ShooterThrowMotor1.setIdleMode(IdleMode.kCoast);
ShooterThrowMotor2.setIdleMode(IdleMode.kCoast);
}

public double getRawEncoderOutput() {
Expand All @@ -81,54 +81,52 @@ public void AngleEncoderReset() {
}

public double getRpmOutput1() {
//return ShooterThrow1Encoder.getVelocity();
return 0.0;
return ShooterThrow1Encoder.getVelocity();
}

public double getRpmOutput2() {
// return ShooterThrow2Encoder.getVelocity() * 600 / 4096.0;
return 0.0;
return ShooterThrow2Encoder.getVelocity() * 600 / 4096.0;
}

public void ShooterThrow1MotorOutput(double value) {
//ShooterThrowMotor1.set(value);
ShooterThrowMotor1.set(value);
}

public void ShooterThrow2MotorOutput(double value) {
//ShooterThrowMotor2.set(value);
ShooterThrowMotor2.set(value);
}

public void ShooterThrowMotorOutput(double value) {
// ShooterThrowMotor1.set(value);
// ShooterThrowMotor2.set(value);
ShooterThrowMotor1.set(value);
ShooterThrowMotor2.set(value);
}

public void ShooterAngleMotorOutput(double value) {
// ShooterAngleMotor.set(value);
ShooterAngleMotor.set(value);
}

public void ShooterThrow1MotorStop() {
// ShooterThrowMotor1.set(0);
ShooterThrowMotor1.set(0);
}

public void ShooterThrow2MotorStop() {
// ShooterThrowMotor2.set(0);
ShooterThrowMotor2.set(0);
}

public void ShooterThrowAllMotorStop() {
// ShooterThrowMotor1.set(0);
//ShooterThrowMotor2.set(0);
ShooterThrowMotor1.set(0);
ShooterThrowMotor2.set(0);
}

public void ShooterAngleMotorStop() {
// ShooterAngleMotor.set(0);
ShooterAngleMotor.set(0);
}

public void ShootertoFeederPos() {
if (!shooterswitch.get()) {
// ShooterAngleMotor.set(0.1);
ShooterAngleMotor.set(0.1);
} else {
// ShooterAngleMotor.stopMotor();
ShooterAngleMotor.stopMotor();

}
}
Expand All @@ -137,7 +135,7 @@ public void ShootertoFeederPos() {
public void periodic() {
SmartDashboard.putNumber("shooter rpm 1", getRpmOutput1());
SmartDashboard.putNumber("shooter rpm 2", getRpmOutput2());
SmartDashboard.putNumber("Shooter degree", getMappedOutput());
SmartDashboard.putNumber("Shooter deqqSAQEgree", getMappedOutput());

if (getshooterswitchvalue()) {
ShooterAngleEncoder.setPosition(0);
Expand Down

0 comments on commit 96cfe46

Please sign in to comment.