Skip to content
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
10 changes: 2 additions & 8 deletions src/org/parts3492/partslib/PARTsCandle.java
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,8 @@ public PARTsCandle(String className, int canID, int ledLength, String canBusName
/*---------------------------------- Custom Private Functions ---------------------------------*/
protected void setColor(Color color) {
setControl(new EmptyAnimation(0));
setControl(new SolidColor(0, LED_LENGTH).withColor(new RGBWColor(color.r, color.g, color.b)));
setControl(
new SolidColor(0, LED_LENGTH).withColor(new RGBWColor(color.r, color.g, color.b)));
}

protected void setNoColor() {
Expand Down Expand Up @@ -412,24 +413,17 @@ public void periodic() {

@Override
public void outputTelemetry() {
super.partsNT.putString("Animation", candle.getAppliedControl().getName());
}

@Override
public void stop() {
// TODO Auto-generated method stub
// throw new UnsupportedOperationException("Unimplemented method 'stop'");
}

@Override
public void reset() {
// TODO Auto-generated method stub
// throw new UnsupportedOperationException("Unimplemented method 'reset'");
}

@Override
public void log() {
// TODO Auto-generated method stub
super.partsLogger.logString("Animation", candle.getAppliedControl().getName());
}
}
120 changes: 66 additions & 54 deletions src/org/parts3492/partslib/PARTsLogger.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ public class PARTsLogger {
/**
* Create a new PARTsLogger.
*
* <p>By default, logging is disabled.
* <p>
* By default, logging is disabled.
*/
public PARTsLogger() {
instantiate(false);
Expand All @@ -43,7 +44,8 @@ public PARTsLogger(boolean allowLogging) {
/**
* Create a new PARTsLogger with the following name.
*
* <p>By default, logging is disabled.
* <p>
* By default, logging is disabled.
*/
public PARTsLogger(String name) {
instantiate(false);
Expand All @@ -65,9 +67,11 @@ public PARTsLogger(String name, boolean allowLogging) {
/**
* Create a new PARTsLogger with the object's class name.
*
* <p>E.g. <code>PARTsLogger</code>.
* <p>
* E.g. <code>PARTsLogger</code>.
*
* <p>By default, logging is disabled.
* <p>
* By default, logging is disabled.
*/
public PARTsLogger(Object o) {
name = o.getClass().getSimpleName();
Expand All @@ -77,7 +81,8 @@ public PARTsLogger(Object o) {
/**
* Create a new PARTsLogger with the object's class name.
*
* <p>E.g. <code>PARTsLogger</code>.
* <p>
* E.g. <code>PARTsLogger</code>.
*
* <p>
*
Expand All @@ -90,11 +95,12 @@ public PARTsLogger(Object o, boolean allowLogging) {

private void instantiate(boolean allowLogging) {
loggingEnabled = allowLogging;
if (loggingEnabled) {
// Starts recording to data log
DataLogManager.start();
if (loggingEnabled) {

if (log == null) log = DataLogManager.getLog();
if (log == null){
// Starts recording to data log
DataLogManager.start();
log = DataLogManager.getLog();}
}
}

Expand All @@ -108,67 +114,73 @@ public void disableLogging() {
instantiate(false);
}

public boolean logBoolean(String key, boolean b) {
if (loggingEnabled) {
public boolean logBoolean(String key, boolean b, boolean logEntry) {
if (loggingEnabled && logEntry) {
new BooleanLogEntry(log, name.length() > 0 ? String.format("%s/%s", name, key) : key)
.append(b);
return true;
} else return false;
} else
return false;
}

public boolean logDouble(String key, double d) {
if (loggingEnabled) {
public boolean logDouble(String key, double d, boolean logEntry) {
if (loggingEnabled && logEntry) {
new DoubleLogEntry(log, name.length() > 0 ? String.format("%s/%s", name, key) : key)
.append(d);
return true;
} else return false;
} else
return false;
}

public boolean logString(String key, String s) {
if (loggingEnabled) {
public boolean logString(String key, String s, boolean logEntry) {
if (loggingEnabled && logEntry) {
new StringLogEntry(log, name.length() > 0 ? String.format("%s/%s", name, key) : key)
.append(s);
return true;
} else return false;
} else
return false;
}

public void logCommandScheduler() {

// Set the scheduler to log events for command initialize, interrupt, finish
CommandScheduler.getInstance()
.onCommandInitialize(
command -> {
logString(command.getName(), "Command initialized");
});
CommandScheduler.getInstance()
.onCommandInterrupt(
command -> {
logString(command.getName(), "Command interrupted");
});
CommandScheduler.getInstance()
.onCommandFinish(
command -> {
logString(command.getName(), "Command finished");
});
public void logCommandScheduler(boolean logEntry) {
if (logEntry) {
// Set the scheduler to log events for command initialize, interrupt, finish
CommandScheduler.getInstance()
.onCommandInitialize(
command -> {
logString(command.getName(), "Command initialized", true);
});
CommandScheduler.getInstance()
.onCommandInterrupt(
command -> {
logString(command.getName(), "Command interrupted", true);
});
CommandScheduler.getInstance()
.onCommandFinish(
command -> {
logString(command.getName(), "Command finished", true);
});
}
}

public void logPathPlanner() {
// Logging callback for target robot pose
PathPlannerLogging.setLogTargetPoseCallback(
(pose) -> {
// Do whatever you want with the pose here
FieldBase.FIELD2D
.getObject("target pose")
.setPose(FieldBase.conditionallyTransformToOppositeAlliance(pose));
});

// Logging callback for the active path, this is sent as a list of poses
PathPlannerLogging.setLogActivePathCallback(
(poses) -> {
// Do whatever you want with the poses here
FieldBase.FIELD2D
.getObject("path")
.setPoses(FieldBase.conditionallyTransformToOppositeAlliance(poses));
});
public void logPathPlanner(boolean logEntry) {
if (logEntry) {
// Logging callback for target robot pose
PathPlannerLogging.setLogTargetPoseCallback(
(pose) -> {
// Do whatever you want with the pose here
FieldBase.FIELD2D
.getObject("target pose")
.setPose(FieldBase.conditionallyTransformToOppositeAlliance(pose));
});

// Logging callback for the active path, this is sent as a list of poses
PathPlannerLogging.setLogActivePathCallback(
(poses) -> {
// Do whatever you want with the poses here
FieldBase.FIELD2D
.getObject("path")
.setPoses(FieldBase.conditionallyTransformToOppositeAlliance(poses));
});
}
}
}
15 changes: 9 additions & 6 deletions src/org/parts3492/partslib/network/PARTsDashboard.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,13 @@

import org.parts3492.partslib.command.IPARTsSubsystem;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.CommandScheduler;

import java.util.ArrayList;

public class PARTsDashboard {
private static DashboardTab state = DashboardTab.AUTONOMOUS;
private static final PARTsNT partsNT = new PARTsNT();

public enum DashboardTab {
AUTONOMOUS("Autonomous"),
Expand All @@ -26,14 +26,17 @@ public enum DashboardTab {
}
}

public PARTsDashboard() {}
public PARTsDashboard() {
}

public static void setSubsystems(ArrayList<IPARTsSubsystem> subsystems) {
subsystems.forEach(s -> SmartDashboard.putData(s));
public static void setSubsystems(ArrayList<IPARTsSubsystem> subsystems, boolean post) {
subsystems.forEach(
s -> partsNT.putSmartDashboardSendable(
s.getName().replace("Phys", "").replace("Sim", ""), s, post));
}

public static void setCommandScheduler() {
SmartDashboard.putData(CommandScheduler.getInstance());
public static void setCommandScheduler(boolean post) {
partsNT.putSmartDashboardSendable("Command Scheduler", CommandScheduler.getInstance(), post);
}

public static void setTab(DashboardTab dashboardState) {
Expand Down
Loading
Loading