Skip to content

Commit

Permalink
Fixed Spelling, commented out some smartdashboard stuff, and removed …
Browse files Browse the repository at this point in the history
…unused variables that deal with intake
  • Loading branch information
BrandonS09 committed Jun 13, 2024
1 parent ea1c79d commit fb1a8ab
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 24 deletions.
2 changes: 1 addition & 1 deletion src/main/java/org/carlmontrobotics/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ public static final class Effectorc {
public static final double[] kV = { 0.122, 0/* 0.065239, 0.077913 */ };
public static final double[] kA = { 0, 0/* 0.0062809,0.05289 */ };
public static final int INTAKE_PORT = 9; // port
public static final int OUTAKE_PORT = 10; // port
public static final int OUTTAKE_PORT = 10; // port
public static final int INTAKE_DISTANCE_SENSOR_PORT = 11; // port
public static final int OUTAKE_DISTANCE_SENSOR_PORT = 10; // port
public static final double DISTANCE_BETWEEN_SENSORS_INCHES = 8.189; // inches
Expand Down
20 changes: 3 additions & 17 deletions src/main/java/org/carlmontrobotics/commands/IntakeNEO.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,29 +10,21 @@

public class IntakeNEO extends Command {
// intake until sees game peice or 4sec has passed
private Timer timer = new Timer();
private final IntakeShooter intake;
double increaseAmount = 0.05;
int index = 0;
public int speed;

public IntakeNEO(IntakeShooter intake) {
addRequirements(this.intake = intake);
SmartDashboard.putNumber("Intake RPM", speed);

}

@Override
public void initialize() {
//TODO: Adjust speed or add in an index
timer.reset();
// TODO: Adjust speed or add in an index;
// if (intake.intakeDetectsNote()) {
// return;
// }
intake.motorSetIntake(.5);
intake.motorSetIntake(.5); // Fast intake speed for initial intake

intake.resetCurrentLimit();
index=0;

}

Expand All @@ -41,20 +33,14 @@ public void initialize() {
public void execute() {
// Intake Led
if((intake.intakeDetectsNote())) {
timer.start();
intake.motorSetIntake(.1);
} else {
timer.stop();
timer.reset();
intake.motorSetIntake(.1); // Slower intake speed triggered after intake ds sees note
}
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
intake.stopIntake();
timer.stop();
index = 0;
//intake.resetCurrentLimit();
}

Expand Down
12 changes: 6 additions & 6 deletions src/main/java/org/carlmontrobotics/subsystems/IntakeShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,8 @@ public class IntakeShooter extends SubsystemBase {
private final CANSparkMax intakeMotor = MotorControllerFactory.createSparkMax(INTAKE_PORT, MotorConfig.NEO);
// private final CANSparkMax outakeMotor =
// MotorControllerFactory.createSparkMax(10, MotorConfig.NEO_550);
private final CANSparkFlex outtakeMotorVortex = new CANSparkFlex(OUTAKE_PORT, MotorType.kBrushless);
private final CANSparkFlex outtakeMotorVortex =
new CANSparkFlex(OUTTAKE_PORT, MotorType.kBrushless);
private final RelativeEncoder outtakeEncoder = outtakeMotorVortex.getEncoder();
private final RelativeEncoder intakeEncoder = intakeMotor.getEncoder();
private final SparkPIDController pidControllerOutake = outtakeMotorVortex.getPIDController();
Expand All @@ -36,7 +37,6 @@ public class IntakeShooter extends SubsystemBase {
private Timer intakeTOFTimer = new Timer();
private Timer outtakeTOFTimer = new Timer();
private int count = 0;
private StringLogEntry tofLogEntry;
private SimpleMotorFeedforward intakeFeedforward = new SimpleMotorFeedforward(kS[INTAKE], kV[INTAKE],
kA[INTAKE]);
private final SimpleMotorFeedforward outtakeFeedforward = new SimpleMotorFeedforward(kS[OUTTAKE], kV[OUTTAKE],
Expand All @@ -61,8 +61,8 @@ public IntakeShooter() {
pidControllerIntake.setI(kI[INTAKE]);
pidControllerIntake.setD(kD[INTAKE]);
SmartDashboard.putData("Intake Shooter", this);
SmartDashboard.putNumber("Intake Ks", kS[INTAKE]);
SmartDashboard.putNumber("Intake Kv", kV[INTAKE]);
// SmartDashboard.putNumber("Intake Ks", kS[INTAKE]);
// SmartDashboard.putNumber("Intake Kv", kV[INTAKE]);
intakeEncoder.setAverageDepth(4);
intakeEncoder.setMeasurementPeriod(8);
// SmartDashboard.putNumber("intake volts", 0);
Expand All @@ -71,8 +71,8 @@ public IntakeShooter() {
intakeDistanceSensor.setRangingMode(RangingMode.Short, 24);// 24 ms is the minimum sample time acc to docs
outtakeDistanceSensor.setRangingMode(RangingMode.Short, 24);
outtakeMotorVortex.setSmartCurrentLimit(60);
SmartDashboard.putNumber("Intake target RPM", 0);
SmartDashboard.putNumber("Vortex volts", 0);
// SmartDashboard.putNumber("Intake target RPM", 0);
// SmartDashboard.putNumber("Vortex volts", 0);
}

public boolean intakeIsOverTemp() {
Expand Down

0 comments on commit fb1a8ab

Please sign in to comment.