Skip to content

Commit

Permalink
Merge branch 'main' into CollectNoteTesting
Browse files Browse the repository at this point in the history
  • Loading branch information
rflood07 authored Jan 30, 2024
2 parents 079b612 + f276197 commit eef468d
Show file tree
Hide file tree
Showing 5 changed files with 41 additions and 67 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -291,6 +291,7 @@ private void registerNamedCommands() {
NamedCommands.registerCommand("stopDrivetrain", new InstantCommand(driveTrain::stop, driveTrain));

if(shooterExists) {NamedCommands.registerCommand("shooterOn", new InstantCommand(()->shooter.shootThing(1), shooter));

NamedCommands.registerCommand("stopFeedingShooter", new InstantCommand(indexer::feederOff, indexer));}
if(indexerExists) {NamedCommands.registerCommand("feedShooter", new InstantCommand(()->indexer.feederFeed(0.5), indexer));}
if(intakeExists) {NamedCommands.registerCommand("autoPickup", new CollectNote(driveTrain, limelight));
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/commands/IndexCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,15 +42,15 @@ public void initialize() {
public void execute() {
if (m_Indexer.getInchesFromSensor()>8) {
intake.intakeYes(1);
m_Indexer.holderRetrieve(0.5);
m_Indexer.on();
shooter.turnOff();
} else {
intake.intakeOff();
m_Indexer.holderOff();
m_Indexer.off();
shooter.shootThing(1);
}
if (shootButtonSupplier.getAsBoolean()) {
m_Indexer.feederFeed(0.5);
m_Indexer.on();
}
}

Expand Down
11 changes: 4 additions & 7 deletions src/main/java/frc/robot/settings/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -248,8 +248,8 @@ private DriveConstants() {
public static final double k_PICKUP_NOTE_tx_D = 0;
}
public static final class ShooterConstants{
public static final int SHOOTER_1_MOTORID = 2491;
public static final int SHOOTER_2_MOTORID = 2491;
public static final int SHOOTER_R_MOTORID = 2491;
public static final int SHOOTER_L_MOTORID = 2491;
public static final int PITCH_MOTOR_ID = 2491;
public static final double SHOOTER_MOTOR_POWER = 1;
public static final double SHOOTING_SPEED_MPS = 10;
Expand Down Expand Up @@ -298,11 +298,8 @@ public static final class ClimberConstants{
public static final double CLIMBER_RPM = 0.1;
}
public static final class IndexerConstants{
public static final int FEEDER_1_MOTOR = 2491;
public static final int FEEDER_2_MOTOR = 2491;
public static final int HOLDER_1_MOTOR = 2491;
public static final int HOLDER_2_MOTOR = 2491;
public static final double INDEXER_SPEED = 0.75;
public static final int INDEXER_MOTOR = 2491;
public static final double INDEXER_SPEED = 2491;
}
public static final class IntakeConstants{
public static final int INTAKE_1_MOTOR = 2491;
Expand Down
60 changes: 17 additions & 43 deletions src/main/java/frc/robot/subsystems/IndexerSubsystem.java
Original file line number Diff line number Diff line change
@@ -1,56 +1,30 @@
package frc.robot.subsystems;

import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkPIDController;
import com.revrobotics.SparkRelativeEncoder;
import com.revrobotics.CANSparkBase.ControlType;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.settings.Constants;
import com.revrobotics.CANSparkLowLevel.MotorType;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.settings.Constants.IndexerConstants;

public class IndexerSubsystem extends SubsystemBase{
CANSparkMax holder1;
CANSparkMax holder2;
CANSparkMax feeder1;
CANSparkMax feeder2;
boolean isHolding;
public IndexerSubsystem(){
CANSparkMax holder1 = new CANSparkMax(IndexerConstants.HOLDER_1_MOTOR, MotorType.kBrushless);
CANSparkMax holder2 = new CANSparkMax(IndexerConstants.HOLDER_2_MOTOR, MotorType.kBrushless);
CANSparkMax feeder1 = new CANSparkMax(IndexerConstants.FEEDER_1_MOTOR, MotorType.kBrushless);
CANSparkMax feeder2 = new CANSparkMax(IndexerConstants.FEEDER_2_MOTOR, MotorType.kBrushless);
//sensor sensorThingy = new ???;
boolean isHolding = false;
feeder2.follow(feeder1);
feeder2.setInverted(true);
holder2.follow(holder1);
holder2.setInverted(true);
holder1.setIdleMode(IdleMode.kBrake);
holder2.setIdleMode(IdleMode.kBrake);
feeder1.setIdleMode(IdleMode.kBrake);
feeder2.setIdleMode(IdleMode.kBrake);
public class IndexerSubsystem extends SubsystemBase {
CANSparkMax m_IndexerMotor;

public IndexerSubsystem() {
m_IndexerMotor = new CANSparkMax(IndexerConstants.INDEXER_MOTOR, MotorType.kBrushless);
}

public double getInchesFromSensor() {
return 0;
}
public void feederFeed(double generalSpeed){
feeder1.set(generalSpeed);
}
public void feederOff(){
feeder1.set(0);
}
public void holderRetrieve(double generalSpeed){
holder1.set(generalSpeed);

public void on() {
m_IndexerMotor.set(IndexerConstants.INDEXER_SPEED);
}
public void holderOff(){
holder1.set(0);

public void off() {
m_IndexerMotor.set(0);
}
public void allOff(){
feeder1.set(0);
holder1.set(0);

public void reverse() {
m_IndexerMotor.set(-IndexerConstants.INDEXER_SPEED);
}
}
30 changes: 16 additions & 14 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@
import java.util.function.BooleanSupplier;

public class ShooterSubsystem extends SubsystemBase {
CANSparkMax shooter1;
CANSparkMax shooter2;
CANSparkMax shooterR;
CANSparkMax shooterL;
CANSparkMax pitchMotor;
double runSpeed;

Expand Down Expand Up @@ -81,19 +81,19 @@ public class ShooterSubsystem extends SubsystemBase {
public ShooterSubsystem(double runSpeed, BooleanSupplier aimAtAmp) {
SparkPIDController shooterPID;
this.aimAtAmp = aimAtAmp;
shooter1 = new CANSparkMax(ShooterConstants.SHOOTER_1_MOTORID, MotorType.kBrushless);
shooter2 = new CANSparkMax(ShooterConstants.SHOOTER_2_MOTORID, MotorType.kBrushless);
shooterR = new CANSparkMax(ShooterConstants.SHOOTER_R_MOTORID, MotorType.kBrushless);
shooterL = new CANSparkMax(ShooterConstants.SHOOTER_L_MOTORID, MotorType.kBrushless);
pitchMotor = new CANSparkMax(ShooterConstants.PITCH_MOTOR_ID, MotorType.kBrushless);
shooter1.restoreFactoryDefaults();
shooter2.follow(shooter1);
shooter2.setInverted(true);
shooter1.setIdleMode(IdleMode.kCoast);
shooter2.setIdleMode(IdleMode.kCoast);
shooterR.restoreFactoryDefaults();
shooterL.follow(shooterR);
shooterL.setInverted(true);
shooterR.setIdleMode(IdleMode.kCoast);
shooterL.setIdleMode(IdleMode.kCoast);


encoder1 = shooter1.getEncoder(SparkRelativeEncoder.Type.kQuadrature, 4096);
encoder1 = shooterR.getEncoder(SparkRelativeEncoder.Type.kQuadrature, 4096);

shooterPID = shooter1.getPIDController();
shooterPID = shooterR.getPIDController();
pitchPID = pitchMotor.getPIDController();

pitchPID.setFF(pitchFeedForward);
Expand Down Expand Up @@ -146,11 +146,13 @@ public ShooterSubsystem(double runSpeed, BooleanSupplier aimAtAmp) {


public void shootThing(double runSpeed) {
shooter1.set(runSpeed);
shooterR.set(runSpeed);
shooterL.set(runSpeed);
}
public void turnOff(){
shooter1.set(0);
}
shooterR.set(0);
shooterL.set(0);
}
public void pitchShooter(double pitchSpeed){
pitchMotor.set(pitchSpeed);
}
Expand Down

0 comments on commit eef468d

Please sign in to comment.