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 all 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"
}
}
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
22 changes: 4 additions & 18 deletions src/main/java/org/carlmontrobotics/commands/IntakeNEO.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,51 +10,37 @@

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(SmartDashboard.getNumber("Intake RPM", speed));
intake.motorSetIntake(.5); // Fast intake speed for initial intake

intake.resetCurrentLimit();
index=0;

}

// 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();
} 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 All @@ -63,6 +49,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();
}
}
25 changes: 11 additions & 14 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(10, 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,7 +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("Intake target RPM", 0);
// SmartDashboard.putNumber("Vortex volts", 0);
}

public boolean intakeIsOverTemp() {
Expand Down Expand Up @@ -141,12 +142,12 @@ public void updateValues() {
@Override
public void periodic() {
updateValues();
double newKS = SmartDashboard.getNumber("Intake Ks", kS[INTAKE]);
double newKV = SmartDashboard.getNumber("Intake Kv", kV[INTAKE]);
// double newKS = SmartDashboard.getNumber("Intake Ks", kS[INTAKE]);
/// double newKV = SmartDashboard.getNumber("Intake Kv", kV[INTAKE]);

if (newKS != intakeFeedforward.ks || newKV != intakeFeedforward.kv) {
intakeFeedforward = new SimpleMotorFeedforward(newKS, newKV);
}
// if (newKS != intakeFeedforward.ks || newKV != intakeFeedforward.kv) {
// intakeFeedforward = new SimpleMotorFeedforward(newKS, newKV);
// }
SmartDashboard.putBoolean("instake ds sees", intakeDetectsNote());
SmartDashboard.putBoolean("outtake ds sees", outtakeDetectsNote());
SmartDashboard.putNumber("intake sample rate", intakeDistanceSensor.getSampleTime());
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