Skip to content

Commit 7fb295c

Browse files
authored
Merge pull request #65 from DeepBlueRobotics/ds-debugging
ds debugging
2 parents b1a1a04 + c8b317c commit 7fb295c

17 files changed

+182
-96
lines changed

networktables.json

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1,10 @@
1-
[]
1+
[
2+
{
3+
"name": "/SmartDashboard/babymode",
4+
"type": "boolean",
5+
"value": false,
6+
"properties": {
7+
"persistent": true
8+
}
9+
}
10+
]

networktables.json.bck

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
[]

simgui.json

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
"/Shuffleboard/arm SysID/quasistatic forward": "Command",
4444
"/SmartDashboard/Arm": "Subsystem",
4545
"/SmartDashboard/Field": "Field2d",
46+
"/SmartDashboard/Intake Shooter": "Subsystem",
4647
"/SmartDashboard/SendableChooser[0]": "String Chooser",
4748
"/SmartDashboard/moveClimber": "Command"
4849
},
@@ -58,10 +59,7 @@
5859
"left": 150,
5960
"right": 2961,
6061
"top": 79,
61-
"width": 16.541748046875,
62-
"window": {
63-
"visible": true
64-
}
62+
"width": 16.541748046875
6563
}
6664
}
6765
},

src/main/java/org/carlmontrobotics/Constants.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -51,12 +51,12 @@ public static final class Effectorc {
5151
public static final int INTAKE = 0;
5252
public static final int OUTTAKE = 1;
5353
// 0.0001184
54-
public static final double[] kP = { /* /Intake/ */ 0.030717, /* /Outake/ */0.0001 };
54+
public static final double[] kP = { 0, 0 /* 0.030717,0.0001 */ };
5555
public static final double[] kI = { /* /Intake/ */0, /* /Outake/ */0 };
5656
public static final double[] kD = { /* /Intake/ */0, /* /Outake/ */0 };
57-
public static final double[] kS = { /* /Intake/ */0.35042, /* /Outake/ */0.29753 * 2 };
58-
public static final double[] kV = { /* /Intake/ */0.065239, /* /Outake/ */0.077913 };
59-
public static final double[] kA = { /* /Intake/ */0.0062809, /* /Outake/ */0.05289 };
57+
public static final double[] kS = { /* /Intake/ */0.22, /* /Outake/ */0.29753 * 2 };
58+
public static final double[] kV = { 0.122, 0/* 0.065239, 0.077913 */ };
59+
public static final double[] kA = { 0, 0/* 0.0062809,0.05289 */ };
6060
public static final int INTAKE_PORT = 9; // port
6161
public static final int OUTAKE_PORT = 10; // port
6262
public static final int INTAKE_DISTANCE_SENSOR_PORT = 11; // port

src/main/java/org/carlmontrobotics/RobotContainer.java

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -212,10 +212,9 @@ private void setBindingsManipulatorNEO() {
212212
new SwitchRPMShootNEO(intakeShooter));
213213
axisTrigger(manipulatorController, Manipulator.SHOOTER_BUTTON)
214214
.onFalse(
215-
new InstantCommand(intakeShooter::stopOutake, intakeShooter));
216-
215+
new InstantCommand(intakeShooter::stopOuttake, intakeShooter));
217216
axisTrigger(manipulatorController, Manipulator.INTAKE_BUTTON)
218-
.onTrue(new SequentialCommandGroup(new PrintCommand("Running Intake"),
217+
.whileTrue(new SequentialCommandGroup(new PrintCommand("Running Intake"),
219218
new IntakeNEO(intakeShooter)));
220219
axisTrigger(manipulatorController, Manipulator.INTAKE_BUTTON)
221220
.onFalse(
@@ -236,15 +235,16 @@ private void setBindingsManipulatorENDEFF() {
236235

237236

238237
new JoystickButton(manipulatorController, Button.kB.value).onTrue(new RampMaxRPM(intakeShooter));
239-
new JoystickButton(manipulatorController, Button.kB.value).onFalse(new InstantCommand(intakeShooter::stopOutake,intakeShooter));
238+
new JoystickButton(manipulatorController, Button.kB.value)
239+
.onFalse(new InstantCommand(intakeShooter::stopOuttake, intakeShooter));
240240
new JoystickButton(manipulatorController, AMP_BUTTON).onTrue(new EjectOuttakeSide(intakeShooter));
241241

242242
axisTrigger(manipulatorController, Manipulator.SHOOTER_BUTTON)
243243
.onTrue(
244244
new SwitchRPMShoot(intakeShooter));
245245
axisTrigger(manipulatorController, Manipulator.SHOOTER_BUTTON)
246246
.onFalse(
247-
new InstantCommand(intakeShooter::stopOutake, intakeShooter));
247+
new InstantCommand(intakeShooter::stopOuttake, intakeShooter));
248248

249249
axisTrigger(manipulatorController, Manipulator.INTAKE_BUTTON)
250250
.onTrue(new SequentialCommandGroup(new PrintCommand("Running Intake"),
@@ -351,10 +351,10 @@ private void registerAutoCommands(){
351351
NamedCommands.registerCommand("PassToOuttake", new PassToOuttake(intakeShooter));
352352

353353
NamedCommands.registerCommand("StopIntake", new InstantCommand(intakeShooter::stopIntake));
354-
NamedCommands.registerCommand("StopOutake", new InstantCommand(intakeShooter::stopOutake));
354+
NamedCommands.registerCommand("StopOutake", new InstantCommand(intakeShooter::stopOuttake));
355355
NamedCommands.registerCommand("StopBoth", new ParallelCommandGroup(
356356
new InstantCommand(intakeShooter::stopIntake),
357-
new InstantCommand(intakeShooter::stopOutake)
357+
new InstantCommand(intakeShooter::stopOuttake)
358358
));
359359
}
360360
private void setupAutos() {

src/main/java/org/carlmontrobotics/commands/Eject.java

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ public void initialize() {
2323
// intakeShooter.setRPMOutake(EJECT_RPM_OUTAKE);
2424
timer.reset();
2525
timer.start();
26-
intakeShooter.setMaxOutake(-1);
26+
intakeShooter.setMaxOuttake(-1);
2727
intakeShooter.setMaxIntake(-1);
2828
}
2929

@@ -36,7 +36,7 @@ public void execute() {
3636
@Override
3737
public void end(boolean interrupted) {
3838
intakeShooter.stopIntake();
39-
intakeShooter.stopOutake();
39+
intakeShooter.stopOuttake();
4040
timer.stop();
4141
intakeShooter.resetCurrentLimit();
4242

@@ -45,6 +45,7 @@ public void end(boolean interrupted) {
4545
// Returns true when the command should end.
4646
@Override
4747
public boolean isFinished() {
48-
return (timer.get() > SMART_CURRENT_LIMIT_TIMEOUT || (!intakeShooter.intakeDetectsNote() && !intakeShooter.outakeDetectsNote()));
48+
return (timer.get() > SMART_CURRENT_LIMIT_TIMEOUT
49+
|| (!intakeShooter.intakeDetectsNote() && !intakeShooter.outtakeDetectsNote()));
4950
}
5051
}

src/main/java/org/carlmontrobotics/commands/EjectOuttakeSide.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ public EjectOuttakeSide(IntakeShooter intakeShooter) {
1717
@Override
1818
public void initialize() {
1919
intakeShooter.setMaxIntake(1);
20-
intakeShooter.setMaxOutake(1);
20+
intakeShooter.setMaxOuttake(1);
2121
timer.reset();
2222
timer.start();
2323
}
@@ -29,13 +29,13 @@ public void execute(){
2929
@Override
3030
public void end(boolean interrupted) {
3131
intakeShooter.stopIntake();
32-
intakeShooter.stopOutake();
32+
intakeShooter.stopOuttake();
3333
timer.stop();
3434

3535

3636
}
3737
@Override
3838
public boolean isFinished() {
39-
return timer.get() >= 4 || (!intakeShooter.intakeDetectsNote() && !intakeShooter.outakeDetectsNote());
39+
return timer.get() >= 4 || (!intakeShooter.intakeDetectsNote() && !intakeShooter.outtakeDetectsNote());
4040
}
4141
}

src/main/java/org/carlmontrobotics/commands/Intake.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,13 +33,13 @@ public void initialize() {
3333
public void execute() {
3434
// Intake Led
3535

36-
if (intake.intakeDetectsNote() && !intake.outakeDetectsNote()) {
36+
if (intake.intakeDetectsNote() && !intake.outtakeDetectsNote()) {
3737
index++;
3838

3939
//intake.setRPMIntake(0);
4040
intake.setRPMIntake(INTAKE_RPM + index*increaseAmount);
4141
}
42-
if (intake.outakeDetectsNote()) {
42+
if (intake.outtakeDetectsNote()) {
4343
// Timer.delay(keepIntakingFor);
4444

4545
intake.setRPMIntake(0.0);
@@ -62,7 +62,7 @@ public void end(boolean interrupted) {
6262
// Returns true when the command should end.
6363
@Override
6464
public boolean isFinished() {
65-
return (intake.intakeDetectsNote() && intake.outakeDetectsNote());
65+
return (intake.intakeDetectsNote() && intake.outtakeDetectsNote());
6666
// || //timer.hasElapsed(MAX_SECONDS_OVERLOAD);
6767

6868
}

src/main/java/org/carlmontrobotics/commands/IntakeNEO.java

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
import org.carlmontrobotics.subsystems.IntakeShooter;
66

77
import edu.wpi.first.wpilibj.Timer;
8+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
89
import edu.wpi.first.wpilibj2.command.Command;
910

1011
public class IntakeNEO extends Command {
@@ -13,17 +14,23 @@ public class IntakeNEO extends Command {
1314
private final IntakeShooter intake;
1415
double increaseAmount = 0.05;
1516
int index = 0;
17+
public int speed;
1618

1719
public IntakeNEO(IntakeShooter intake) {
1820
addRequirements(this.intake = intake);
21+
SmartDashboard.putNumber("Intake RPM", speed);
1922

2023
}
2124

2225
@Override
2326
public void initialize() {
2427
//TODO: Adjust speed or add in an index
2528
timer.reset();
26-
intake.motorSetIntake(0.6);
29+
// if (intake.intakeDetectsNote()) {
30+
// return;
31+
// }
32+
intake.motorSetIntake(SmartDashboard.getNumber("Intake RPM", speed));
33+
2734
intake.resetCurrentLimit();
2835
index=0;
2936

@@ -32,6 +39,7 @@ public void initialize() {
3239
// Called every time the scheduler runs while the command is scheduled.
3340
@Override
3441
public void execute() {
42+
intake.motorSetIntake(SmartDashboard.getNumber("Intake RPM", speed));
3543
// Intake Led
3644
if((intake.intakeDetectsNote())) {
3745
timer.start();
@@ -53,8 +61,8 @@ public void end(boolean interrupted) {
5361
// Returns true when the command should end.
5462
@Override
5563
public boolean isFinished() {
56-
return intake.intakeDetectsNote() && timer.get()>0.1;
64+
// return intake.intakeDetectsNote() && timer.get()>0.1;
5765
// || //timer.hasElapsed(MAX_SECONDS_OVERLOAD);
58-
66+
return intake.intakeDetectsNote();
5967
}
6068
}

src/main/java/org/carlmontrobotics/commands/IntakeTesting.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@ public void initialize() {
2020
}
2121
@Override
2222
public void execute() {
23-
if(!intakeShooter.outakeDetectsNote()) {
23+
if (!intakeShooter.outtakeDetectsNote()) {
2424
intakeShooter.setRPMIntake(startingRPMWithNote+increaseRPM*index);
2525
index++;
2626
SmartDashboard.putNumber("RPM Used", increaseRPM*index + startingRPMWithNote);
@@ -33,6 +33,6 @@ public void end(boolean interrupted) {
3333
SmartDashboard.putNumber("finalRPMUsed", increaseRPM*index + startingRPMWithNote);
3434
}
3535
public boolean isFinished() {
36-
return intakeShooter.outakeDetectsNote();
36+
return intakeShooter.outtakeDetectsNote();
3737
}
3838
}

0 commit comments

Comments
 (0)