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

Commit

Permalink
pushes
Browse files Browse the repository at this point in the history
  • Loading branch information
MorphaxTheDeveloper committed Mar 16, 2024
1 parent 91189ae commit f48ce7d
Show file tree
Hide file tree
Showing 17 changed files with 558 additions and 48 deletions.
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,11 @@ public void teleopInit() {
if (m_autonomousCommand != null) {
m_autonomousCommand.cancel();
}
m_robotContainer.m_intake.StopAngleMotor();
m_robotContainer.m_intake.StopNoteMotor();
m_robotContainer.m_shooter.throwStop();
m_robotContainer.m_feeder.stop();
m_robotContainer.swerveSubsystem.stopModules();
}

@Override
Expand Down
221 changes: 177 additions & 44 deletions src/main/java/frc/robot/RobotContainer.java

Large diffs are not rendered by default.

89 changes: 89 additions & 0 deletions src/main/java/frc/robot/commands/Intake/SwitchAuto.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
// 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.Intake;

import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.commands.common.fedleme;
import frc.robot.subsystems.FeederSubsystem;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.subsystems.JoystickSubsystem;
import frc.robot.subsystems.ShooterSubsystem;

public class SwitchAuto extends Command {
IntakeSubsystem m_intake;
boolean dursunmu;
FeederSubsystem m_feeder;
JoystickSubsystem m_joystick;
ShooterSubsystem m_shooter;
boolean varmi = false;


public SwitchAuto(IntakeSubsystem m_intake, boolean dursunmu) {

this.m_intake = m_intake;
}

// Called when the command is initially scheduled.
@Override
public void initialize() {

}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {


boolean ilkswitch;
boolean ikinciswitch;

ilkswitch = m_intake.intakedetector1.get();
ikinciswitch = m_intake.intakedetector2.get();






if(!dursunmu){

if(ikinciswitch && ilkswitch){

m_intake.getNote();

}else{

m_intake.StopNoteMotor();
varmi = true;
}
}



// if(varmi){
// m_intake.getNote();
// }



SmartDashboard.putBoolean("asdadssdaasd", ilkswitch);
SmartDashboard.putBoolean("asdadssdaasd2222", ikinciswitch);
}

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

// Returns true when the command should end.
@Override
public boolean isFinished() {
return varmi;
}

}
49 changes: 49 additions & 0 deletions src/main/java/frc/robot/commands/Shooter/TurnForShooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
// 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.Shooter;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj2.command.PIDCommand;
import frc.robot.Constants.DriveConstants;
import frc.robot.subsystems.NetworkSubsystem;
import frc.robot.subsystems.SwerveSubsystem;

// 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 TurnForShooter extends PIDCommand {
/** Creates a new TurnForShooter. */
public TurnForShooter(NetworkSubsystem m_net,SwerveSubsystem m_swerve) {
super(
// The controller that the command will use
new PIDController(0.05, 0, 0),
// This should return the measurement
() -> m_net.getX(),
// This should return the setpoint (can also be a constant)
() -> 0,
// This uses the output
output -> {
// Use the output here
ChassisSpeeds chassisSpeeds = new ChassisSpeeds(0, 0, -output * 0.05);

// 5. Convert chassis speeds to individual module states
SwerveModuleState[] moduleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates(chassisSpeeds);

// 6. Output each module states to wheels
m_swerve.setModuleStates(moduleStates);
});
// Use addRequirements() here to declare subsystem dependencies.
// Configure additional PID options by calling `getController` here.
getController().setTolerance(10);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return getController().atSetpoint();
}
}
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/commands/Shooter/VisionShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,8 @@ public VisionShooter(ShooterSubsystem m_shooter, NetworkSubsystem m_network) {
/* try {
m_shooter.ShooterAngleMotorOutput(output * .13);
Thread.sleep(150); // 2 saniye durakla
m_shooter.ShooterAngleMotorStop();
m_shooter.ShooterAn
gleMotorStop();
} catch (InterruptedException e) {
e.printStackTrace();
}*/
Expand Down
41 changes: 41 additions & 0 deletions src/main/java/frc/robot/commands/Shooter/VisionSwerve.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
package frc.robot.commands.Shooter;


import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.PIDCommand;
import frc.robot.Constants;
import frc.robot.subsystems.NetworkSubsystem;
import frc.robot.subsystems.ShooterSubsystem;

public class VisionSwerve extends PIDCommand {

public VisionSwerve(ShooterSubsystem m_shooter, NetworkSubsystem m_network) {
super(

new PIDController(0.004,
0.01,
Constants.values.shooter.PidShooterAngleKD),
() -> m_network.getX(),
() -> m_network.getTarget(),
output -> {
/* try {
m_shooter.ShooterAngleMotorOutput(output * .13);
Thread.sleep(150); // 2 saniye durakla
m_shooter.ShooterAngleMotorStop();
} catch (InterruptedException e) {
e.printStackTrace();
}*/

m_shooter.ShooterAngleMotorOutput(output * .13);
});

addRequirements(m_shooter);
getController().setTolerance(5);

}

@Override
public boolean isFinished() {
return false;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,12 @@

import java.util.function.Supplier;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.PIDCommand;
import frc.robot.Constants.DriveConstants;
import frc.robot.Constants.OIConstants;
import frc.robot.subsystems.SwerveSubsystem;
Expand Down
37 changes: 37 additions & 0 deletions src/main/java/frc/robot/commands/common/otofeedleme.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
// 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.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.commands.Intake.GetNote;
import frc.robot.commands.Intake.IntakeModeChange;
import frc.robot.commands.Intake.PidIntakeCommand;
import frc.robot.commands.Intake.RunTillSwitch;
import frc.robot.commands.Shooter.ShooterModeChange;
import frc.robot.commands.feeder.FeederRunTillSwitch;
import frc.robot.commands.feeder.otoFeederRun;
import frc.robot.subsystems.FeederSubsystem;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.subsystems.JoystickSubsystem;
import frc.robot.subsystems.ShooterSubsystem;

public class otofeedleme extends SequentialCommandGroup {
/** Creates a new fedleme. */
public otofeedleme(IntakeSubsystem m_intake, FeederSubsystem m_feeder, JoystickSubsystem m_joystick, ShooterSubsystem m_shooter) {

addCommands(
new InstantCommand(()-> m_shooter.ShootertoFeederPos())
.andThen(new IntakeModeChange(m_joystick, 0))
.alongWith(new WaitCommand(1).andThen(new InstantCommand(()-> m_intake.otogetNote())))
.alongWith(new FeederRunTillSwitch(m_feeder, false, m_intake))



);
}
}
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/commands/common/pickup.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
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)));
addCommands(new RunTillSwitch(m_intake,false).alongWith(new IntakeModeChange(m_joystick, 1))
.until(()-> m_intake.intakeTwoStich())
.andThen(new IntakeModeChange(m_joystick, 0)));
}
}
25 changes: 25 additions & 0 deletions src/main/java/frc/robot/commands/common/pickupforAuto.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
// 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.commands.Intake.SwitchAuto;
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 pickupforAuto extends SequentialCommandGroup {
/** Creates a new pickup. */
public pickupforAuto(IntakeSubsystem m_intake, JoystickSubsystem m_joystick) {
addCommands(new RunTillSwitch(m_intake,false).alongWith(new IntakeModeChange(m_joystick, 1))
.until(()-> m_intake.intakeTwoStich())
.andThen(new IntakeModeChange(m_joystick, 3)));
}
}
61 changes: 61 additions & 0 deletions src/main/java/frc/robot/commands/feeder/otoFeederRun.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
// 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.feeder;

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

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


public otoFeederRun(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.
@Override
public void initialize() {

}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {


if(m_feeder.varmi){
if(m_feeder.detector()){
m_feeder.otobackward2();
}
else{
m_feeder.stop();
m_intake.StopNoteMotor();
m_feeder.varmifalse();

}}






}

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

// Returns true when the command should end.
@Override
public boolean isFinished() {
return dursunmu;
}

}
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 @@ -41,9 +41,13 @@ public boolean detector() {
}

public void backward2() {
feedmotor.set(-0.54);
}
public void otobackward2() {
feedmotor.set(-0.70);
}


public void backward() {
feedmotor.set(-0.9);
}
Expand Down
12 changes: 12 additions & 0 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,9 @@ public void NewIntakeMotorOutput(double value) {
public void getNote() {
intakeMotor1.set(0.67);
}
public void otogetNote() {
intakeMotor1.set(0.7);
}


public void pushNote() {
Expand Down Expand Up @@ -116,6 +119,15 @@ public Boolean intakeswitch2() {
return intakedetector2.get();
}

public Boolean intakeTwoStich(){
if(!intakedetector2.get()|| !intakedetector1.get()){
return true;
}
else{
return false;
}
}

@Override
public void periodic() {
SmartDashboard.putNumber("intake", getRawEncoderOutput());
Expand Down
Loading

0 comments on commit f48ce7d

Please sign in to comment.