Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Intake changes #69

Merged
merged 5 commits into from
Jun 13, 2024
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .DataLogTool/datalogtool.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"download": {
"localDir": "C:\\Users\\Deep Blue\\Downloads",
"serverTeam": "199"
"serverTeam": "10.1.99.2"
}
}
6 changes: 3 additions & 3 deletions src/main/java/org/carlmontrobotics/commands/IntakeNEO.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ public void initialize() {
// if (intake.intakeDetectsNote()) {
// return;
// }
intake.motorSetIntake(SmartDashboard.getNumber("Intake RPM", speed));
intake.motorSetIntake(.5);
BrandonS09 marked this conversation as resolved.
Show resolved Hide resolved

intake.resetCurrentLimit();
index=0;
Expand All @@ -39,10 +39,10 @@ public void initialize() {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
intake.motorSetIntake(SmartDashboard.getNumber("Intake RPM", speed));
// Intake Led
if((intake.intakeDetectsNote())) {
timer.start();
BrandonS09 marked this conversation as resolved.
Show resolved Hide resolved
intake.motorSetIntake(.1);
} else {
timer.stop();
timer.reset();
Expand All @@ -63,6 +63,6 @@ public void end(boolean interrupted) {
public boolean isFinished() {
// return intake.intakeDetectsNote() && timer.get()>0.1;
// || //timer.hasElapsed(MAX_SECONDS_OVERLOAD);
return intake.intakeDetectsNote();
return intake.outtakeDetectsNote();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ 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(10, MotorType.kBrushless);
private final CANSparkFlex outtakeMotorVortex = new CANSparkFlex(OUTAKE_PORT, MotorType.kBrushless);
BrandonS09 marked this conversation as resolved.
Show resolved Hide resolved
private final RelativeEncoder outtakeEncoder = outtakeMotorVortex.getEncoder();
private final RelativeEncoder intakeEncoder = intakeMotor.getEncoder();
private final SparkPIDController pidControllerOutake = outtakeMotorVortex.getPIDController();
Expand Down Expand Up @@ -72,6 +72,7 @@ public IntakeShooter() {
outtakeDistanceSensor.setRangingMode(RangingMode.Short, 24);
outtakeMotorVortex.setSmartCurrentLimit(60);
SmartDashboard.putNumber("Intake target RPM", 0);
SmartDashboard.putNumber("Vortex volts", 0);
BrandonS09 marked this conversation as resolved.
Show resolved Hide resolved
}

public boolean intakeIsOverTemp() {
Expand Down Expand Up @@ -174,10 +175,6 @@ else if (rangingModeOuttake == TimeOfFlight.RangingMode.Medium)
// outakeMotor.set(SmartDashboard.getNumber("intake volts", 0));

// count++;

// double volts = SmartDashboard.getNumber("Vortex volts", 0);
// outakeMotorVortex.set(volts);

// setMaxOutake();

SmartDashboard.putNumber("Intake amps", intakeMotor.getOutputCurrent());
Expand Down
Loading