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
10 changes: 10 additions & 0 deletions .DataLogTool/datalogtool.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
{
"download": {
"deleteAfter": false,
"localDir": "C:\\Users\\Joshua Moran\\Documents\\logs\\mrt",
"serverTeam": "10.59.85.2"
},
"output": {
"outputFolder": "C:\\Users\\Joshua Moran\\Documents\\logs\\mrt"
}
}
15 changes: 10 additions & 5 deletions src/main/java/frc/robot/Config.java
Original file line number Diff line number Diff line change
Expand Up @@ -102,16 +102,21 @@ public class Config {
*
* This value should be set to 1 at a comp. This is for linear tuning, which can easily be done by anyone. For illinear tuning (i.e its off by different amounts at different points go to Adam, don't mess with the equation.)
* */
public static final double kLimelightShooterSpeedModiferPercentage = 1;//1.010375;
public static final double kLimelightShooterSpeedModiferPercentage = 1.65;//1.010375;
public static final double kLimelightShooterCTerm = 500;
public static final double kLimelightTuningOffset = 0;

//y = 3077.128 + (1786 - 3077.128)/(1 + (x/55.07565)^6.788735)

public static final double kLimelightATerm = 1722.884;
public static final double kLimelightBTerm = 5.779675;
public static final double kLimelightCTerm = 603.8564;
public static final double kLimelightDTerm = 445984300;
public static final double kLimelightATerm = 1684.135;
public static final double kLimelightBTerm = 5.531879;
public static final double kLimelightCTerm = 599.2879;
public static final double kLimelightDTerm = 256575100;

public static final double kLimelightAcceptableAngle =3.5;

//Diagnostics

public static final double kLowPressureWarn = 20; //PSI

}
112 changes: 112 additions & 0 deletions src/main/java/frc/robot/DriverInterface.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,9 @@
package frc.robot;

import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.util.datalog.DataLog;
import edu.wpi.first.util.datalog.DoubleLogEntry;
import edu.wpi.first.util.datalog.StringLogEntry;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.GenericHID.RumbleType;
Expand All @@ -25,6 +28,34 @@ public class DriverInterface {

private final SendableChooser<String> verboseOutputChooser = new SendableChooser<>();

private DoubleLogEntry batteryVoltage;
private DoubleLogEntry totalCurrent;
private DoubleLogEntry channel0Current;
private DoubleLogEntry channel1Current;
private DoubleLogEntry channel2Current;
private DoubleLogEntry channel3Current;
private DoubleLogEntry channel4Current;
private DoubleLogEntry channel5Current;
private DoubleLogEntry channel6Current;
private DoubleLogEntry channel7Current;
private DoubleLogEntry channel8Current;
private DoubleLogEntry channel9Current;
private DoubleLogEntry channel10Current;
private DoubleLogEntry channel11Current;
private DoubleLogEntry channel12Current;
private DoubleLogEntry channel13Current;
private DoubleLogEntry channel14Current;
private DoubleLogEntry channel15Current;
private DoubleLogEntry channel16Current;
private DoubleLogEntry channel17Current;
private DoubleLogEntry channel18Current;
private DoubleLogEntry channel19Current;
private DoubleLogEntry channel20Current;
private DoubleLogEntry channel21Current;
private DoubleLogEntry channel22Current;
private DoubleLogEntry channel23Current;
private StringLogEntry consoleErrorOutput;


public DriverInterface() {

Expand Down Expand Up @@ -163,12 +194,15 @@ public void consoleOutput(MessageType messageType, String message) {
break;
case CAUTION:
System.out.println("CAUTION " + message);
consoleErrorOutput.append("CAUTION " + message, 0);
break;
case WARNING:
System.out.println("WARNING " + message);
consoleErrorOutput.append("WARNING " + message, 0);
break;
case CRITICAL:
System.out.println("⚠ CRITICAL " + message + " ⚠ ");
consoleErrorOutput.append("⚠ CRITICAL " + message + " ⚠ ", 0);
break;
}
}
Expand Down Expand Up @@ -603,6 +637,10 @@ public void initSmartDashboard() {
SmartDashboard.putBoolean("Foward direction", getRobotFowardDirection() == RobotFowardDirection.FRONT);
SmartDashboard.putNumber("Shooter target", 2000);
SmartDashboard.putNumber("Vision TUNING", 5);

SmartDashboard.putNumber("Shooter Offset Multiplier", Config.kLimelightShooterSpeedModiferPercentage);
SmartDashboard.putNumber("Shooter C Term", Config.kLimelightShooterCTerm);

try {
SmartDashboard.putNumber("Pressure", Pneumatics.getInstance().getPressure());
} catch (Exception e) {
Expand Down Expand Up @@ -630,6 +668,14 @@ public double getShooterRatioDenomonatorField() {
return SmartDashboard.getNumber("Shooter Ratio Denomonator", 1);
}

public double getShooterOffsetMultiplier() {
return SmartDashboard.getNumber("Shooter Offset Multiplier", Config.kLimelightShooterSpeedModiferPercentage);
}

public double getShooterCTerm() {
return SmartDashboard.getNumber("Shooter C Term", Config.kLimelightShooterCTerm);
}


//xbox controlller y
// x b
Expand Down Expand Up @@ -683,6 +729,72 @@ public void rumble() {
}
}

public void initLogging(DataLog aLog) {

batteryVoltage = new DoubleLogEntry(aLog, "Battery Voltage");
totalCurrent = new DoubleLogEntry(aLog, "Total Current");
channel0Current = new DoubleLogEntry(aLog, "Channel 0 current");
channel1Current = new DoubleLogEntry(aLog, "Channel 1 current");
channel2Current = new DoubleLogEntry(aLog, "Channel 2 current");
channel3Current = new DoubleLogEntry(aLog, "Channel 3 current");
channel4Current = new DoubleLogEntry(aLog, "Channel 4 current");
channel5Current = new DoubleLogEntry(aLog, "Channel 5 current");
channel6Current = new DoubleLogEntry(aLog, "Channel 6 current");
channel7Current = new DoubleLogEntry(aLog, "Channel 7 current");
channel8Current = new DoubleLogEntry(aLog, "Channel 8 current");
channel9Current = new DoubleLogEntry(aLog, "Channel 9 current");
channel10Current = new DoubleLogEntry(aLog, "Channel 10 current");
channel11Current = new DoubleLogEntry(aLog, "Channel 11 current");
channel12Current = new DoubleLogEntry(aLog, "Channel 12 current");
channel13Current = new DoubleLogEntry(aLog, "Channel 13 current");
channel14Current = new DoubleLogEntry(aLog, "Channel 14 current");
channel15Current = new DoubleLogEntry(aLog, "Channel 15 current");
channel16Current = new DoubleLogEntry(aLog, "Channel 16 current");
channel17Current = new DoubleLogEntry(aLog, "Channel 17 current");
channel18Current = new DoubleLogEntry(aLog, "Channel 18 current");
channel19Current = new DoubleLogEntry(aLog, "Channel 19 current");
channel20Current = new DoubleLogEntry(aLog, "Channel 20 current");
channel21Current = new DoubleLogEntry(aLog, "Channel 21 current");
channel22Current = new DoubleLogEntry(aLog, "Channel 22 current");
channel23Current = new DoubleLogEntry(aLog, "Channel 23 current");

consoleErrorOutput = new StringLogEntry(aLog, "Error log");
consoleErrorOutput.append("Logging start", 0);

}

public void updateLogging(long aTime) {
batteryVoltage.append(RobotMap.getPDH().getVoltage(), aTime);
totalCurrent.append(RobotMap.getPDH().getTotalCurrent(), aTime);
channel0Current.append(RobotMap.getPDH().getCurrent(0), aTime);
channel1Current.append(RobotMap.getPDH().getCurrent(1), aTime);
channel2Current.append(RobotMap.getPDH().getCurrent(2), aTime);
channel3Current.append(RobotMap.getPDH().getCurrent(3), aTime);
channel4Current.append(RobotMap.getPDH().getCurrent(4), aTime);
channel5Current.append(RobotMap.getPDH().getCurrent(5), aTime);
channel6Current.append(RobotMap.getPDH().getCurrent(6), aTime);
channel7Current.append(RobotMap.getPDH().getCurrent(7), aTime);
channel8Current.append(RobotMap.getPDH().getCurrent(8), aTime);
channel9Current.append(RobotMap.getPDH().getCurrent(9), aTime);
channel10Current.append(RobotMap.getPDH().getCurrent(10), aTime);
channel11Current.append(RobotMap.getPDH().getCurrent(11), aTime);
channel12Current.append(RobotMap.getPDH().getCurrent(12), aTime);
channel13Current.append(RobotMap.getPDH().getCurrent(13), aTime);
channel14Current.append(RobotMap.getPDH().getCurrent(14), aTime);
channel15Current.append(RobotMap.getPDH().getCurrent(15), aTime);
channel16Current.append(RobotMap.getPDH().getCurrent(16), aTime);
channel17Current.append(RobotMap.getPDH().getCurrent(17), aTime);
channel18Current.append(RobotMap.getPDH().getCurrent(18), aTime);
channel19Current.append(RobotMap.getPDH().getCurrent(19), aTime);
channel20Current.append(RobotMap.getPDH().getCurrent(20), aTime);
channel21Current.append(RobotMap.getPDH().getCurrent(21), aTime);
channel22Current.append(RobotMap.getPDH().getCurrent(22), aTime);
channel23Current.append(RobotMap.getPDH().getCurrent(23), aTime);



}




Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,7 @@ public void robotInit() {
FrontIntake.getInstance().initLogging(log);
Pneumatics.getInstance().initLogging(log);
Shooter.getInstance().initLogging(log);
VisionTrack.getInstance().initLogging(log);
}


Expand All @@ -116,6 +117,7 @@ public void robotPeriodic() {
FrontIntake.getInstance().updateLogging(logTime);
Pneumatics.getInstance().updateLogging(logTime);
Shooter.getInstance().updateLogging(logTime);
VisionTrack.getInstance().updateLogging(logTime);

Shuffleboard.update();

Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/autonomous/CompletedSequences.java
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ private static Sequence createPos1Complex()
t1.setAngle(-84.75);
autoDrive d1 = new autoDrive();
d1.setAngle(-84.75);
d1.setDist(-.82);
d1.setDist(-.6);
d1.setSpeed(0.85);
d1.setAccFwdLimit(0.15);
d1.setAccRevLimit(0.17);
Expand Down Expand Up @@ -136,7 +136,7 @@ private static Sequence createPos1Complex()
t3.setAngle(0);
autoDrive d4 = new autoDrive();
d4.setAngle(0);
d4.setDist(-1.8875);//NICE
d4.setDist(-1.15);
d4.setSpeed(0.9);
d4.setAccFwdLimit(0.15);
d4.setAccRevLimit(0.22);
Expand Down Expand Up @@ -273,7 +273,7 @@ private static Sequence createPos4Normal()
d3.setDist(1.5);
d3.setSpeed(0.3);
autoTurn t4 = new autoTurn();
t4.setAngle(210);
t4.setAngle(180);
autoBallDetectionLimelight ball2 = new autoBallDetectionLimelight();
ball2.setNumBalls(5);
autoEjector eject2 = new autoEjector();
Expand Down
18 changes: 17 additions & 1 deletion src/main/java/frc/robot/subsystems/BackIntake.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
import com.ctre.phoenix.motorcontrol.ControlMode;

import edu.wpi.first.util.datalog.DataLog;
import edu.wpi.first.util.datalog.DoubleLogEntry;
import edu.wpi.first.util.datalog.*;
import frc.robot.Config;
import frc.robot.RobotMap;

Expand All @@ -28,6 +28,9 @@ public static enum BackIntakeStates {
// DataLog variables
private DoubleLogEntry logRearInSpeed;
private DoubleLogEntry logRearInStatorCurrent;
private StringLogEntry logRearInCurrentState;
private StringLogEntry logRearInDesiredState;


public BackIntake() {

Expand Down Expand Up @@ -108,6 +111,13 @@ public BackIntakeStates getCurrentState() {
return currentState;
}

/**
* @return The desired state of the intakes
*/
public BackIntakeStates getDesiredState() {
return desiredState;
}

/**
* @param State to become the intake desired state.
*/
Expand Down Expand Up @@ -139,12 +149,18 @@ public void initLogging(DataLog aLog)
{
logRearInSpeed = new DoubleLogEntry(aLog, "Rear Intake Speed");
logRearInStatorCurrent = new DoubleLogEntry(aLog, "Rear Intake Stator Current");
logRearInCurrentState = new StringLogEntry(aLog, "Rear Intake Current State");
logRearInDesiredState = new StringLogEntry(aLog, "Rear Intake Desired State");

}

public void updateLogging(long aTime)
{
logRearInSpeed.append(BackIntake.getInstance().getSpeed(), aTime);
logRearInStatorCurrent.append(BackIntake.getInstance().getStatorCurrent(), aTime);
logRearInCurrentState.append(getCurrentState().toString(), aTime);
logRearInDesiredState.append(getDesiredState().toString(), aTime);

}

}
Loading