Skip to content

Commit

Permalink
eller geldi
Browse files Browse the repository at this point in the history
  • Loading branch information
MorphaxTheDeveloper committed Mar 13, 2024
1 parent 7ede5af commit 4865e59
Show file tree
Hide file tree
Showing 3 changed files with 160 additions and 24 deletions.
93 changes: 69 additions & 24 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.SwerveControllerCommand;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Constants.DriveConstants;
Expand All @@ -44,12 +45,14 @@
import frc.robot.commands.Shooter.ShooterModeChange;
import frc.robot.commands.Shooter.ShooterSetDegree;
import frc.robot.commands.Swerve.SwerveJoystickCmd;
import frc.robot.commands.autonomous.AutoNoteShoot;
import frc.robot.commands.common.FeedingPosition;
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.ArmSubsystem;
import frc.robot.subsystems.FeederSubsystem;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.subsystems.JoystickSubsystem;
Expand All @@ -66,6 +69,7 @@ public class RobotContainer {
private final XboxController driverJoytick = new XboxController(1);
private final XboxController subJoytick = new XboxController(3);
private final FeederSubsystem m_feeder = new FeederSubsystem();
private final ArmSubsystem m_arm = new ArmSubsystem();
private final JoystickSubsystem m_joystick = new JoystickSubsystem();
public int autonomous_case;

Expand Down Expand Up @@ -112,6 +116,17 @@ private void configureBindings() {
//button 3
// TIRMANMA new JoystickButton(driverJoytick, 1).whileTrue(new InstantCommand(()-> m_feeder.forward()));

new JoystickButton(driverJoytick, 5).whileTrue(new InstantCommand(()-> m_arm.leftarmup()));
new JoystickButton(driverJoytick, 6).whileTrue(new InstantCommand(()-> m_arm.rightarmup()));

new JoystickButton(driverJoytick, 7).whileTrue(new InstantCommand(()-> m_arm.leftarmdown()));
new JoystickButton(driverJoytick, 8).whileTrue(new InstantCommand(()-> m_arm.rightarmdown()));

new JoystickButton(driverJoytick, 5).whileFalse(new InstantCommand(()-> m_arm.leftarmstop()));
new JoystickButton(driverJoytick, 6).whileFalse(new InstantCommand(()-> m_arm.rightarmstop()));

new JoystickButton(driverJoytick, 7).whileFalse(new InstantCommand(()-> m_arm.leftarmstop()));
new JoystickButton(driverJoytick, 8).whileFalse(new InstantCommand(()-> m_arm.rightarmstop()));

/*
____ _ _ ____ ____ ____ __ _ _ ____ ____
Expand Down Expand Up @@ -171,17 +186,17 @@ private void configureBindings() {
//Driver
// 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, 6).whileTrue(new InstantCommand(()-> m_intake.pushNote()));
// new JoystickButton(driverJoytick, 6).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(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()));



Expand Down Expand Up @@ -329,17 +344,39 @@ public Command getAutonomousCommand() {

var trajectoryOne =
TrajectoryGenerator.generateTrajectory(
new Pose2d(0, 0, new Rotation2d(0)),
List.of(new Translation2d(-1.28, 0),new Translation2d(-0.56, -0.91)),
new Pose2d(-1.28, -1.44, new Rotation2d(3.1)),
new Pose2d(-1, -1, new Rotation2d(0)),
List.of(new Translation2d(0, -1)),
new Pose2d(0.0, -1, new Rotation2d(0)),
trajectoryConfig);

// var trajectoryOne =
// TrajectoryGenerator.generateTrajectory(
// new Pose2d(0, 0, new Rotation2d(0)),
// List.of(new Translation2d(-1.28, 0),new Translation2d(-0.56, -0.91)),
// new Pose2d(-1.28, -1.44, new Rotation2d(3.1)),
// trajectoryConfig);

var trajectoryTwo =
TrajectoryGenerator.generateTrajectory(
new Pose2d(-1.28, -1.44, new Rotation2d(0)),
new Pose2d(-1.28, -1.44, new Rotation2d(3.1)),
List.of(new Translation2d(-1.28, 0),new Translation2d(0.5, -0.5)),
new Pose2d(-0,0, new Rotation2d(0)),
trajectoryConfig);

var trajectoryF =
TrajectoryGenerator.generateTrajectory(
new Pose2d(0, 0, new Rotation2d(0)),
List.of(new Translation2d(-0.60, 0),new Translation2d(-1, 0)),
new Pose2d(-1.28, 0, new Rotation2d(0)),
trajectoryConfig);

var trajectoryP =
TrajectoryGenerator.generateTrajectory(
new Pose2d(-1.28, 0, new Rotation2d(0)),
List.of(new Translation2d(-0.70, 0),new Translation2d(-0.35, 0)),
new Pose2d(-0,0, new Rotation2d(0)),
trajectoryConfig);


var trajectoryThree =
TrajectoryGenerator.generateTrajectory(
Expand All @@ -350,15 +387,17 @@ public Command getAutonomousCommand() {

var goSecondNote =
TrajectoryGenerator.generateTrajectory(
List.of(new Pose2d(0,0, new Rotation2d(0)),
new Pose2d(-1.3,0, new Rotation2d(0))),
trajectoryConfig);
new Pose2d(0, 0, new Rotation2d(0)),
List.of(new Translation2d(-1.3, 0)),
new Pose2d(-1.3,0, new Rotation2d(0)),
trajectoryConfig);

var secondNoteToSpeaker =
TrajectoryGenerator.generateTrajectory(
List.of(new Pose2d(-1.3,0, new Rotation2d(0)),
new Pose2d(0,0, new Rotation2d(0))),
trajectoryConfig);
new Pose2d(-1.3, 0, new Rotation2d(0)),
List.of(new Translation2d(-1.3, 0),new Translation2d(0,0)),
new Pose2d(0,0, new Rotation2d(0)),
trajectoryConfig);


// var trajectoryOne =
Expand Down Expand Up @@ -400,19 +439,25 @@ public Command getAutonomousCommand() {
// swerveSubsystem::OtosetModuleStates,
// swerveSubsystem);

switch(autonomous_case) {
case 0: // Önce içindekini atacak sonrasında arkasındakini atıp atabiliyorsa onu oradan atacak sonra en arkadaki
return pathCommand(goSecondNote).andThen(pathCommand(secondNoteToSpeaker));
// switch(autonomous_case) {

// case 0: // Önce içindekini atacak sonrasında arkasındakini atıp atabiliyorsa onu oradan atacak sonra en arkadaki
// return new AutoNoteShoot(m_shooter, m_feeder, () -> 70);
// //Command(goSecondNote).andThen(pathCommand(secondNoteToSpeaker));

case 1:
// case 1:

case 2:
// case 2:

default: return pathCommand(goSecondNote).andThen(pathCommand(secondNoteToSpeaker));
}
// default: return new AutoNoteShoot(m_shooter, m_feeder, () -> 70);
// //pathCommand(goSecondNote).andThen(pathCommand(secondNoteToSpeaker));
// }



return new AutoNoteShoot(m_shooter, m_feeder, () -> 60).withTimeout(2).andThen(pathCommand(trajectoryOne));

//return pathCommand(trajectoryF).andThen(pathCommand(trajectoryP));

// return swerveControllerCommand.andThen(swerveControllerCommand2).andThen(swerveControllerCommand3);
// PathPlannerPath path = PathPlannerPath.fromPathFile("New New Path");
// Create a path following command using AutoBuilder. This will also trigger event markers.
Expand Down
35 changes: 35 additions & 0 deletions src/main/java/frc/robot/commands/autonomous/AutoNoteShoot.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
// 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.autonomous;

import java.util.function.DoubleSupplier;

import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.commands.Shooter.ShooterSetDegree;
import frc.robot.subsystems.FeederSubsystem;
import frc.robot.subsystems.ShooterSubsystem;

// 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 AutoNoteShoot extends SequentialCommandGroup {
/** Creates a new AutoNoteShoot. */
public AutoNoteShoot(ShooterSubsystem m_shooter, FeederSubsystem m_feeder, DoubleSupplier degree) {
// Add your commands in the addCommands() call, e.g.
// addCommands(new FooCommand(), new BarCommand());
addCommands(
new ShooterSetDegree(m_shooter, degree).
withTimeout(1).
alongWith(new InstantCommand(() -> m_shooter.ShooterThrowMotorOutput(-0.6))
.andThen(new WaitCommand(0.6))
.andThen(new InstantCommand(() -> m_feeder.backward()).withTimeout(0.5)))
.andThen(new InstantCommand(() -> m_shooter.ShooterThrowMotorOutput(0))
.andThen(new InstantCommand(() -> m_feeder.stop())))
);
}
}
56 changes: 56 additions & 0 deletions src/main/java/frc/robot/subsystems/ArmSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
// 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.subsystems;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class ArmSubsystem extends SubsystemBase {
CANSparkMax armleft = new CANSparkMax(16, MotorType.kBrushless);
CANSparkMax armright = new CANSparkMax(13, MotorType.kBrushless);

public ArmSubsystem() {
armleft.setIdleMode(IdleMode.kBrake);
armright.setIdleMode(IdleMode.kBrake);

}


public void rightarmup(){
armright.set(0.6);
}

public void rightarmdown(){
armright.set(-0.6);

}

public void leftarmup(){
armleft.set(-0.6);

}

public void leftarmdown(){
armleft.set(0.6);

}
public void leftarmstop(){
armleft.set(0);

}
public void rightarmstop(){
armright.set(0);

}


@Override
public void periodic() {
// This method will be called once per scheduler run
}
}

0 comments on commit 4865e59

Please sign in to comment.