Skip to content
Open
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
92 changes: 92 additions & 0 deletions simgui-ds.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
{
"keyboardJoysticks": [
{
"axisConfig": [
{
"decKey": 65,
"incKey": 68
},
{
"decKey": 87,
"incKey": 83
},
{
"decKey": 69,
"decayRate": 0.0,
"incKey": 82,
"keyRate": 0.009999999776482582
}
],
"axisCount": 3,
"buttonCount": 4,
"buttonKeys": [
90,
88,
67,
86
],
"povConfig": [
{
"key0": 328,
"key135": 323,
"key180": 322,
"key225": 321,
"key270": 324,
"key315": 327,
"key45": 329,
"key90": 326
}
],
"povCount": 1
},
{
"axisConfig": [
{
"decKey": 74,
"incKey": 76
},
{
"decKey": 73,
"incKey": 75
}
],
"axisCount": 2,
"buttonCount": 4,
"buttonKeys": [
77,
44,
46,
47
],
"povCount": 0
},
{
"axisConfig": [
{
"decKey": 263,
"incKey": 262
},
{
"decKey": 265,
"incKey": 264
}
],
"axisCount": 2,
"buttonCount": 6,
"buttonKeys": [
260,
268,
266,
261,
269,
267
],
"povCount": 0
},
{
"axisCount": 0,
"buttonCount": 0,
"povCount": 0
}
]
}
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,15 @@ public enum Mode {
public static final Mode currentMode = RobotBase.isReal() ? Mode.REAL : simMode;

public static final int NEO_CURRENT_LIMIT = 20;
public static final int NEO_CURRENT_LIMIT_2 = 40;

// Logging
public static final long MAX_LOG_TIME_WAIT = 10;
public static final boolean ENABLE_LOGGING = true;

public static final boolean DEBUG = true;
public static final int ROLLER_MOTOR_ID = 1;
public static final int INTAKE_MOTOR_ID = 3;
public static final int TILT_MOTOR_ID = 2;

public static final double ROLLER_SPEED = 0.25;
Expand Down
16 changes: 15 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,12 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.commands.Flush;
import frc.robot.commands.Intake;
import frc.robot.commands.roller.SpinRoller;
import frc.robot.commands.tilt.TiltDown;
import frc.robot.commands.tilt.TiltUp;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.TiltSubsystem;
import frc.robot.utils.simulation.RobotVisualizer;
Expand All @@ -25,7 +28,7 @@ public class RobotContainer {
// The robot's subsystems and commands are defined here...
private final RollerSubsystem rollerSubsystem;
private final TiltSubsystem tiltSubsystem;

private final IntakeSubsystem intakeSubsystem;
private RobotVisualizer robotVisualizer;

/**
Expand All @@ -36,15 +39,18 @@ public RobotContainer() {
case REAL -> {
rollerSubsystem = new RollerSubsystem(RollerSubsystem.createRealIo());
tiltSubsystem = new TiltSubsystem(TiltSubsystem.createRealIo());
intakeSubsystem = new IntakeSubsystem(IntakeSubsystem.createRealIo());
}
case REPLAY -> {
rollerSubsystem = new RollerSubsystem(RollerSubsystem.createMockIo());
tiltSubsystem = new TiltSubsystem(TiltSubsystem.createMockIo());
intakeSubsystem = new IntakeSubsystem(IntakeSubsystem.createMockIo());
}
case SIM -> {
robotVisualizer = new RobotVisualizer();
rollerSubsystem = new RollerSubsystem(RollerSubsystem.createSimIo(robotVisualizer));
tiltSubsystem = new TiltSubsystem(TiltSubsystem.createSimIo(robotVisualizer));
intakeSubsystem = new IntakeSubsystem(IntakeSubsystem.createSimIo(robotVisualizer));
}
default -> {
throw new RuntimeException("Did not specify Robot Mode");
Expand Down Expand Up @@ -93,6 +99,14 @@ public void putShuffleboardCommands() {
SmartDashboard.putData(
"Tilt Down",
new TiltDown(tiltSubsystem));

SmartDashboard.putData(
"Intake",
new Intake(intakeSubsystem));

SmartDashboard.putData(
"Flush",
new Flush(intakeSubsystem));
}
}

Expand Down
43 changes: 43 additions & 0 deletions src/main/java/frc/robot/commands/Flush.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
package frc.robot.commands;
import edu.wpi.first.wpilibj.Timer;
import frc.robot.Constants;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.utils.logging.commands.LoggableCommand;

public class Flush extends LoggableCommand {
private final IntakeSubsystem subsystem;
private final Timer timer;

/**
* @param subsystem
*/
public Flush(IntakeSubsystem subsystem) {
timer = new Timer();
this.subsystem = subsystem;
addRequirements(subsystem);
}

@Override
public void initialize() {
timer.restart();
}

@Override
public void execute() {
subsystem.setSpeed(Constants.ROLLER_SPEED);
}

@Override
public void end(boolean interrupted) {
subsystem.stopMotors();
}

@Override
public boolean isFinished() {
if (timer.hasElapsed(Constants.SPIN_TIMEOUT)) {
return true;
} else{
return false;
}
}
}
43 changes: 43 additions & 0 deletions src/main/java/frc/robot/commands/Intake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
package frc.robot.commands;
import edu.wpi.first.wpilibj.Timer;
import frc.robot.Constants;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.utils.logging.commands.LoggableCommand;

public class Intake extends LoggableCommand {
private final IntakeSubsystem subsystem;
private final Timer timer;

/**
* @param subsystem
*/
public Intake(IntakeSubsystem subsystem) {
timer = new Timer();
this.subsystem = subsystem;
addRequirements(subsystem);
}

@Override
public void initialize() {
timer.restart();
}

@Override
public void execute() {
subsystem.setSpeed(Constants.ROLLER_SPEED);
}

@Override
public void end(boolean interrupted) {
subsystem.stopMotors();
}

@Override
public boolean isFinished() {
if (timer.hasElapsed(Constants.SPIN_TIMEOUT)) {
return true;
} else{
return false;
}
}
}
69 changes: 69 additions & 0 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
package frc.robot.subsystems;

import com.revrobotics.spark.SparkBase;
import com.revrobotics.spark.SparkLowLevel;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.config.SparkBaseConfig;
import com.revrobotics.spark.config.SparkMaxConfig;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.logging.io.motor.MockSparkMaxIo;
import frc.robot.utils.logging.io.motor.RealSparkMaxIo;
import frc.robot.utils.logging.io.motor.SimSparkMaxIo;
import frc.robot.utils.logging.io.motor.SparkMaxIo;
import frc.robot.utils.simulation.MotorSimulator;
import frc.robot.utils.simulation.RobotVisualizer;

public class IntakeSubsystem extends SubsystemBase {

public static final String LOGGING_NAME = "IntakeSubsystem";
private final SparkMaxIo Io;

public IntakeSubsystem(SparkMaxIo Io) {
this.Io = Io;
}

public void setSpeed(double speed) {
Io.set(speed);
}

public void stopMotors() {
Io.stopMotor();
}

@Override
public void periodic() {
Io.periodic();
}

public static SparkMaxIo createMockIo() {
return new MockSparkMaxIo();
}

public static SparkMaxIo createRealIo() {
return new RealSparkMaxIo(LOGGING_NAME, createMotor(), MotorLoggableInputs.allMetrics());
}

public static SparkMaxIo createSimIo(RobotVisualizer visualizer) {
SparkMax motor = createMotor();
return new SimSparkMaxIo(LOGGING_NAME, motor, MotorLoggableInputs.allMetrics(),
new MotorSimulator(motor, visualizer.getIntakeLigament()));
}

private static SparkMax createMotor() {
SparkMax motor = new SparkMax(Constants.INTAKE_MOTOR_ID, SparkLowLevel.MotorType.kBrushless);
SparkMaxConfig motorConfig = new SparkMaxConfig();
motorConfig.idleMode(SparkBaseConfig.IdleMode.kBrake);
motorConfig.smartCurrentLimit(Constants.NEO_CURRENT_LIMIT_2);
motor.configure(
motorConfig,
SparkBase.ResetMode.kResetSafeParameters,
SparkBase.PersistMode.kPersistParameters);
//changed constructor name

return motor;
}
}


15 changes: 8 additions & 7 deletions src/main/java/frc/robot/subsystems/RollerSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,23 +21,23 @@

public class RollerSubsystem extends SubsystemBase {
public static final String LOGGING_NAME = "RollerSubsystem";
private final SparkMaxIo io;
private final SparkMaxIo motor;

public RollerSubsystem(SparkMaxIo io) {
this.io = io;
public RollerSubsystem(SparkMaxIo motor) {
this.motor = motor;
}

public void setSpeed(double speed) {
io.set(speed);
motor.set(speed);
}

public void stopMotors() {
io.stopMotor();
motor.stopMotor();
}

@Override
public void periodic() {
io.periodic();
motor.periodic();
}

public static SparkMaxIo createMockIo() {
Expand All @@ -63,7 +63,8 @@ private static SparkMax createMotor() {
motorConfig,
SparkBase.ResetMode.kResetSafeParameters,
SparkBase.PersistMode.kPersistParameters);
//changed constructor name

return motor;
return motor;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ public class LoggableSequentialCommandGroup extends SequentialCommandGroup imple
private String basicName = getClass().getSimpleName();
private Command parent = new BlankCommand();

public <T extends Command & Loggable> LoggableSequentialCommandGroup(T... commands) {
public <T extends Command & Loggable> LoggableSequentialCommandGroup(T...commands) {
ProxyCommand[] proxyCommands = new ProxyCommand[commands.length];
for (int i = 0; i < commands.length; i++) {
commands[i].setParent(this);
Expand Down
1 change: 0 additions & 1 deletion src/main/java/frc/robot/utils/logging/io/BaseIoImpl.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.robot.utils.logging.io;

import frc.robot.utils.logging.io.BaseIo;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.inputs.LoggableInputs;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
import frc.robot.Constants;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.simulation.Simulator;
import org.littletonrobotics.junction.mechanism.LoggedMechanismLigament2d;

/**
* IO Implementation for a simulated SparkMax IO controller.
Expand Down
Loading