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

Current Dashboard #82

Merged
merged 6 commits into from
Apr 26, 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
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

public class Constants {

public class Drive {
public static class Drive {
public static final double MAXIMUM_VELOCITY = 5.5; // meters per second
public static final double MAXIMUM_ANGULAR_VELOCITY = 8; // radians per second

Expand All @@ -27,7 +27,7 @@ public class Drive {
public static final double ROTATION_TARGET_RANGE = 1.5;
}

public class Arm {
public static class Arm {
// Encoder constants
public static final int ENCODER_CHANNEL = 7;
public static final int ENCODER_CHANNEL_B = 29;
Expand Down Expand Up @@ -98,7 +98,7 @@ public class Auto {
public static final PathConstraints EXTRA_PATHFINDING_CONSTRAINTS = new PathConstraints(3, 3, 9.4, 12.5);
}

public class Shooter {
public static class Shooter {
public static final double SHOOT_SPEED = 1700;
public static final double AMP_SHOOT_SPEED = SHOOT_SPEED * 0.4;
public static final double LONG_SHOT_SPEED = 3500;
Expand Down Expand Up @@ -131,12 +131,12 @@ public class Shooter {
public static final double INDEXER_MOI = 1;
}

public class Dashboard {
public static class Dashboard {
public static final boolean DISABLE_TUNER = false;
public static final String VERSION_FILE_NAME = "version/.robotVersionMini";
}

public class Controller {
public static class Controller {
public static final double DEADZONE_CONSTANT = 0.1675;

public static final double RUMBLE_POWER = 1;
Expand All @@ -151,11 +151,11 @@ public class Controller {
public static final int RIGHT_TRIGGER = 3;
}

public class LEDController {
public static class LEDController {
public static final int LED_CONTROLLER_CHANNEL = 0;
}

public class Undertaker {
public static class Undertaker {
public static final int INTAKE_MOTOR_ONE = 13;
public static final int INTAKE_MOTOR_TWO = 14;

Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ public RobotContainer() {
operatorController = new CommandXboxController(Constants.Controller.OPERATOR_CONTROLLER);

Dashboards.initVoltageDashboard();
Dashboards.initCurrentDashboard();
Dashboards.initMemoryDashboard();
VersionFile.getInstance().putToDashboard();

Expand Down
10 changes: 10 additions & 0 deletions src/main/java/frc/robot/shooter/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,10 @@
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.Constants;
import frc.robot.Robot;

Expand Down Expand Up @@ -92,8 +95,15 @@ public void setIndexerSpeed(double targetSpeed) {
shooterIO.setIndexerOutput(targetIndexerSpeed);
}

public Command testMotor() {
return new InstantCommand(() -> shooterIO.setShooterOutput(0.1, 0))
.andThen(new WaitCommand(2))
.andThen(() -> shooterIO.setShooterOutput(0, 0));
}

@Override
public void periodic() {

topOutput = topPidController.calculate(shooterIO.getShooterSpeeds()[0], targetTopShooterSpeed)
+ topFeedForward.calculate(targetTopShooterSpeed);
bottomOutput = bottomPidController.calculate(shooterIO.getShooterSpeeds()[1], targetBottomShooterSpeed)
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/shooter/SimShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ public boolean isIndexerLoaded() {

@Override
public double[] getShooterSpeeds() {
return new double[] {topShooterMotorSim.getAngularVelocityRPM(), bottomShooterMotorSim.getAngularVelocityRPM()};
return new double[] {shooterTopVoltage, shooterBottomVoltage};
}

@Override
Expand Down
24 changes: 24 additions & 0 deletions src/main/java/frc/robot/util/Dashboards.java
Original file line number Diff line number Diff line change
@@ -1,12 +1,16 @@
package frc.robot.util;

import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.PowerDistribution.ModuleType;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;

public class Dashboards {
private static boolean voltageNeedsInit = true;
private static boolean currentNeedsInit = true;
private static boolean memoryNeedsInit = true;
private static final PowerDistribution PDH = new PowerDistribution(1, ModuleType.kRev);

public static void initVoltageDashboard() {
if (voltageNeedsInit) {
Expand All @@ -21,6 +25,26 @@ public static void initVoltageDashboard() {
}
}

public static void initCurrentDashboard() {
if (currentNeedsInit) {
ShuffleboardTab tab = Shuffleboard.getTab("Current Info");
// Arm Motors
tab.addDouble("Right Arm Motor Current", () -> PDH.getCurrent(18));
tab.addDouble("Left Arm Motor Current", () -> PDH.getCurrent(5));
// Shooter Motors
tab.addDouble("Shooter Motor Top Current", () -> PDH.getCurrent(12));
tab.addDouble("Shooter Motor Bottom Current", () -> PDH.getCurrent(7));
tab.addDouble("Indexer Motor Top Current", () -> PDH.getCurrent(13));
tab.addDouble("Indexer Motor Bottom Current", () -> PDH.getCurrent(6));
// Undertaker Motors
tab.addDouble("Undertaker left Motor Current", () -> PDH.getCurrent(4));

// Drive Motors

currentNeedsInit = false;
}
}

public static void initMemoryDashboard() {
if (memoryNeedsInit) {
Runtime r = Runtime.getRuntime();
Expand Down