Skip to content

Commit

Permalink
Log everything
Browse files Browse the repository at this point in the history
  • Loading branch information
varun7654 committed Jan 8, 2024
1 parent 6d92b31 commit a34246d
Show file tree
Hide file tree
Showing 7 changed files with 31 additions and 10 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ public RobotContainer() {
drive
),
drive::resetOdometry,
false,
true,
this
);

Expand Down
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/subsystems/arm/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,12 @@

import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.subsystems.arm.ArmIO.ArmInputs;
import org.littletonrobotics.junction.Logger;

public class Arm extends SubsystemBase {

ArmIO io;
ArmInputs inputs = new ArmInputs();
ArmInputsAutoLogged inputs = new ArmInputsAutoLogged();

public Arm(ArmIO io) {
this.io = io;
Expand All @@ -26,8 +26,12 @@ public void setArmPosition(double position) {
@Override
public void periodic() {
io.updateInputs(inputs);
Logger.getInstance().processInputs("Arm", inputs);

io.setArmPosition(targetPosition, feedforward.calculate(inputs.armPositionRad, inputs.armVelocityRadPerSec));
double armffvoltage = feedforward.calculate(inputs.armPositionRad, inputs.armVelocityRadPerSec);
Logger.getInstance().recordOutput("ArmFFVoltage", armffvoltage);

io.setArmPosition(targetPosition, armffvoltage);
}

public double getArmPosition() {
Expand Down
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/subsystems/arm/ArmIO.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
package frc.robot.subsystems.arm;

import org.littletonrobotics.junction.AutoLog;

public interface ArmIO {
@AutoLog
public static class ArmInputs {
public double armPositionRad = 0.0;
public double armVelocityRadPerSec = 0.0;
Expand Down
9 changes: 7 additions & 2 deletions src/main/java/frc/robot/subsystems/climber/Climber.java
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
package frc.robot.subsystems.climber;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.subsystems.climber.ClimberIO.ClimberInputs;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

public class Climber extends SubsystemBase {

ClimberIO io;
ClimberInputs inputs = new ClimberInputs();
ClimberInputsAutoLogged inputs = new ClimberInputsAutoLogged();

LoggedDashboardNumber climberStartPosition = new LoggedDashboardNumber("Climb Start Position", 32);

Expand Down Expand Up @@ -47,6 +47,11 @@ public void extendClimber() {
@Override
public void periodic() {
io.updateInputs(inputs);
Logger.getInstance().processInputs("Climber", inputs);

Logger.getInstance().recordOutput("ClimberState", state.toString());
Logger.getInstance().recordOutput("ClimberTargetPower", targetPower);
Logger.getInstance().recordOutput("ClimberTargetPosition", targetPosition);

switch (state) {
case IDLE -> {
Expand Down
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/subsystems/climber/ClimberIO.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
package frc.robot.subsystems.climber;

import org.littletonrobotics.junction.AutoLog;

public interface ClimberIO {
@AutoLog
public class ClimberInputs {
public double climberPosition = 0.0;
public double climberVelocity = 0.0;
Expand Down
11 changes: 7 additions & 4 deletions src/main/java/frc/robot/subsystems/intake/Intake.java
Original file line number Diff line number Diff line change
@@ -1,28 +1,31 @@
package frc.robot.subsystems.intake;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.subsystems.intake.IntakeIO.IntakeInputs;
import org.littletonrobotics.junction.Logger;

public class Intake extends SubsystemBase {

IntakeIO io;
IntakeInputs inputs = new IntakeInputs();
IntakeInputsAutoLogged inputs = new IntakeInputsAutoLogged();

public Intake(IntakeIO io) {
this.io = io;
}

public void setPrimaryIntakeVelocity(double leftVelocity) {
io.setPrimaryIntakeVelocity(leftVelocity);
public void setPrimaryIntakeVelocity(double velocity) {
io.setPrimaryIntakeVelocity(velocity);
Logger.getInstance().recordOutput("PrimaryIntakeTargetVelocity", velocity);
}

public void setSecondaryIntakeVelocity(double velocity) {
io.setSecondaryIntakeVelocity(velocity);
Logger.getInstance().recordOutput("SecondaryIntakeTargetVelocity", velocity);
}

@Override
public void periodic() {
io.updateInputs(inputs);
Logger.getInstance().processInputs("Intake", inputs);
}

public double getPrimaryIntakeVelocity() {
Expand Down
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/subsystems/intake/IntakeIO.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
package frc.robot.subsystems.intake;

import org.littletonrobotics.junction.AutoLog;

public interface IntakeIO {
@AutoLog
public static class IntakeInputs {
public double primaryIntakeVoltage = 0.0;
public double primaryIntakeCurrent = 0.0;
Expand Down

0 comments on commit a34246d

Please sign in to comment.