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

Use AdvantageKit logging #93

Draft
wants to merge 9 commits into
base: main
Choose a base branch
from
Draft
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
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -160,3 +160,6 @@ bin/

# Simulation GUI and other tools window save file
*-window.json

# AdvantageKit git metadata
src/main/java/frc/robot/BuildConstants.java
28 changes: 28 additions & 0 deletions build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2023.4.2"
id "com.peterabeles.gversion" version "1.10"
}

sourceCompatibility = JavaVersion.VERSION_17
Expand Down Expand Up @@ -71,6 +72,9 @@ dependencies {
testImplementation 'org.junit.jupiter:junit-jupiter-api:5.8.2'
testImplementation 'org.junit.jupiter:junit-jupiter-params:5.8.2'
testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.8.2'

def akitJson = new groovy.json.JsonSlurper().parseText(new File(projectDir.getAbsolutePath() + "/vendordeps/AdvantageKit.json").text)
annotationProcessor "org.littletonrobotics.akit.junction:junction-autolog:$akitJson.version"
}

test {
Expand Down Expand Up @@ -100,3 +104,27 @@ wpi.java.configureTestTasks(test)
tasks.withType(JavaCompile) {
options.compilerArgs.add '-XDstringConcat=inline'
}

repositories {
maven {
url = uri("https://maven.pkg.github.com/Mechanical-Advantage/AdvantageKit")
credentials {
username = "Mechanical-Advantage-Bot"
password = "\u0067\u0068\u0070\u005f\u006e\u0056\u0051\u006a\u0055\u004f\u004c\u0061\u0079\u0066\u006e\u0078\u006e\u0037\u0051\u0049\u0054\u0042\u0032\u004c\u004a\u006d\u0055\u0070\u0073\u0031\u006d\u0037\u004c\u005a\u0030\u0076\u0062\u0070\u0063\u0051"
}
}
}

configurations.all {
exclude group: "edu.wpi.first.wpilibj"
}

project.compileJava.dependsOn(createVersionFile)
gversion {
srcDir = "src/main/java/"
classPackage = "frc.robot"
className = "BuildConstants"
dateFormat = "yyyy-MM-dd HH:mm:ss z"
timeZone = "America/Los_Angeles"
indent = " "
}
19 changes: 0 additions & 19 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -160,13 +160,6 @@ public static final class LEDConstants {
public static final int LED_LENGTH = 144;
}

public static final class GripperConstants {
public static final int PFFT_FORWARD_IDL = 0;
public static final int PFFT_REVERSE_IDL = 1;
public static final int PFFT_FORWARD_IDR = 2;
public static final int PFFT_REVERSE_IDR = 3;
}

public static final class RollerConstants {
public static final int OPEN_ID = 12;
public static final int LEFT_ID = 13;
Expand All @@ -175,16 +168,4 @@ public static final class RollerConstants {

public static final double ALLOW_OPEN_EXTENSION_METERS = Units.inchesToMeters(17);
}

public static final class MoverConstants {
public static final int ROTATION_MOTOR_PORT = 4;
public static final int ROTATION_FOLLOWER_MOTOR_PORT = 5;
public static final int EXTENSION_MOTOR_PORT = 19;

public static final double ROTATION_GEAR_RATIO = 1/155.91;
public static final double EXTENSION_GEAR_RATIO = 1/27;

public static final double ANGLE_OFFSET_SPEED = 0.001;
public static final double EXTENSION_OFFSET_SPEED = 0.001;
}
}
40 changes: 38 additions & 2 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,16 @@

package frc.robot;

import edu.wpi.first.wpilibj.TimedRobot;
import org.littletonrobotics.junction.LogFileUtil;
import org.littletonrobotics.junction.LoggedRobot;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.inputs.LoggedPowerDistribution;
import org.littletonrobotics.junction.networktables.NT4Publisher;
import org.littletonrobotics.junction.wpilog.WPILOGReader;
import org.littletonrobotics.junction.wpilog.WPILOGWriter;

import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.PowerDistribution.ModuleType;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
Expand All @@ -17,13 +26,40 @@
* the package after creating this project, you must also update the build.gradle file in the
* project.
*/
public class Robot extends TimedRobot {
public class Robot extends LoggedRobot {
private RobotContainer robotContainer;
private Command autonomousCommand;
private Command testCommand;

@Override
public void robotInit() {
Logger logger = Logger.getInstance();

logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME);
logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE);
logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA);
logger.recordMetadata("GitDate", BuildConstants.GIT_DATE);
logger.recordMetadata("GitBranch", BuildConstants.GIT_BRANCH);
logger.recordMetadata("GitDirty", switch (BuildConstants.DIRTY) {
case 0 -> "All changes committed";
case 1 -> "Uncommitted changes";
default -> "Unknown";
});

if (isReal()) {
// TODO: folder path
logger.addDataReceiver(new WPILOGWriter("/media/sda1/"));
logger.addDataReceiver(new NT4Publisher());
LoggedPowerDistribution.getInstance(1, ModuleType.kRev); // TODO: module ID
} else {
setUseTiming(false);
String logPath = LogFileUtil.findReplayLog();
logger.setReplaySource(new WPILOGReader(logPath));
logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim")));
}

logger.start();

// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
robotContainer = new RobotContainer();
Expand Down
27 changes: 20 additions & 7 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,12 @@

package frc.robot;

import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
Expand Down Expand Up @@ -46,7 +49,12 @@
import frc.robot.vision.PhotonWrapper;
import frc.robot.subsystems.drivetrain.TankSubsystem;
import frc.robot.subsystems.leds.LEDSubsystem;
import frc.robot.subsystems.roller.RollerIO;
import frc.robot.subsystems.roller.RollerIOReal;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.ElevatorState;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorIO;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorIOReal;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;
import frc.robot.subsystems.tiltedelevator.ElevatorState.OffsetState;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
Expand All @@ -55,7 +63,6 @@
import frc.robot.subsystems.drivetrain.SwerveSubsystem;
import frc.robot.subsystems.drivetrain.SwerveSubsystem2020;
import frc.robot.subsystems.drivetrain.BaseDrivetrain;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.Superstructure;

/**
Expand Down Expand Up @@ -102,7 +109,7 @@ public class RobotContainer {

// Commands
private final ShuffleboardTab shuffleboardTab = Shuffleboard.getTab("Driver");
private final SendableChooser<Command> autonChooser;
private final LoggedDashboardChooser<Command> autonChooser;
private final MotorTestCommand testCommand;

private final BaseBalancerCommand balancerCommand;
Expand All @@ -119,18 +126,24 @@ public RobotContainer() {

signalLEDSubsystem = new LEDSubsystem();

if (RobotBase.isReal()) {
rollerSubsystem = new RollerSubsystem(new RollerIOReal());
tiltedElevatorSubsystem = new TiltedElevatorSubsystem(new TiltedElevatorIOReal());
} else {
rollerSubsystem = new RollerSubsystem(new RollerIO() {});
tiltedElevatorSubsystem = new TiltedElevatorSubsystem(new TiltedElevatorIO() {});
}

// driveSubsystem = new MissileShellSwerveSubsystem();
driveSubsystem = new SwerveSubsystem(photonWrapper, signalLEDSubsystem);
rollerSubsystem = new RollerSubsystem();
tiltedElevatorSubsystem = new TiltedElevatorSubsystem();

superstructure = new Superstructure(rollerSubsystem, tiltedElevatorSubsystem, signalLEDSubsystem, switchableCamera);

balancerCommand = new DefaultBalancerCommand(driveSubsystem);

// Initialize auton and test commands
autonChooser = new SendableChooser<>();
autonChooser.setDefaultOption("Skip auton", new InstantCommand());
autonChooser = new LoggedDashboardChooser<>("Auton/Path");
autonChooser.addDefaultOption("Skip auton", new InstantCommand());

if (driveSubsystem instanceof BaseSwerveSubsystem) {
final BaseSwerveSubsystem swerveSubsystem = (BaseSwerveSubsystem) driveSubsystem;
Expand Down Expand Up @@ -306,7 +319,7 @@ private void configureMechBindings() {
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {
return autonChooser.getSelected();
return autonChooser.get();
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
import frc.robot.commands.balancing.DefaultBalancerCommand;
import frc.robot.commands.balancing.GoOverCommand;
import frc.robot.positions.PlacePosition;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

public class BalanceAndTaxiAutonSequence extends BaseAutonSequence {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@

import frc.robot.commands.balancing.DefaultBalancerCommand;
import frc.robot.positions.PlacePosition;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

public class BalanceAutonSequence extends BaseAutonSequence {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
import frc.robot.commands.swerve.FollowPathCommand;
import frc.robot.commands.swerve.SwerveIdleCommand;
import frc.robot.positions.PlacePosition;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.ElevatorState;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
import frc.robot.commands.swerve.FollowPathCommand;
import frc.robot.positions.FieldPosition;
import frc.robot.positions.PlacePosition;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

public class BottomBalanceAutonSequence extends BaseAutonSequence {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
import frc.robot.commands.swerve.FollowPathCommand;
import frc.robot.positions.FieldPosition;
import frc.robot.positions.PlacePosition;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

public class BottomOnePieceAutonSequence extends BaseAutonSequence {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
import frc.robot.commands.swerve.FollowPathCommand;
import frc.robot.positions.FieldPosition;
import frc.robot.positions.PlacePosition;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.ElevatorState;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package frc.robot.commands.auton;

import frc.robot.positions.PlacePosition;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

public class PreloadedOnlyAutonSequence extends BaseAutonSequence {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
import frc.robot.commands.swerve.FollowPathCommand;
import frc.robot.positions.FieldPosition;
import frc.robot.positions.PlacePosition;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

public class TopOnePieceAutonSequence extends BaseAutonSequence {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@

import frc.robot.positions.FieldPosition;
import frc.robot.positions.PlacePosition;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.ElevatorState;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@

import frc.robot.commands.grabber.RollerPlaceCommand;
import frc.robot.commands.mover.TiltedElevatorCommand;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseDrivetrain;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.ElevatorState;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;
import frc.robot.subsystems.tiltedelevator.ElevatorState.OffsetState;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;

import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseDrivetrain;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.tiltedelevator.ElevatorState;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

Expand Down
19 changes: 0 additions & 19 deletions src/main/java/frc/robot/commands/grabber/GripperIntakeCommand.java

This file was deleted.

19 changes: 0 additions & 19 deletions src/main/java/frc/robot/commands/grabber/GripperPlaceCommand.java

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@

import edu.wpi.first.wpilibj2.command.CommandBase;

import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.RollerSubsystem.HeldPiece;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem.HeldPiece;

/**
* Intakes 1 game piece with the roller mech. This command runs the rollers at a set power
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.CommandBase;

import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.RollerSubsystem.HeldPiece;
import frc.robot.subsystems.roller.RollerSubsystem;
import frc.robot.subsystems.roller.RollerSubsystem.HeldPiece;

/**
* Places 1 game piece with the roller mech. This command runs the rollers in reverse
Expand Down
Loading