diff --git a/.classpath b/.classpath
index 86166cc..47a8ba9 100644
--- a/.classpath
+++ b/.classpath
@@ -12,8 +12,12 @@
-
+
-
+
+
+
+
+
diff --git a/src/main/java/com/spartronics4915/frc2019/Robot.java b/src/main/java/com/spartronics4915/frc2019/Robot.java
index 515f383..660e134 100755
--- a/src/main/java/com/spartronics4915/frc2019/Robot.java
+++ b/src/main/java/com/spartronics4915/frc2019/Robot.java
@@ -35,7 +35,6 @@ public class Robot extends TimedRobot
private CargoChute mCargoChute = null;
private CargoIntake mCargoIntake = null;
private Climber mClimber = null;
- private LED mLED = null;
private RobotStateEstimator mRobotStateEstimator = null;
private Superstructure mSuperstructure = null;
private AutoModeExecutor mAutoModeExecutor;
@@ -100,10 +99,10 @@ public void robotInit()
mCargoChute = CargoChute.getInstance();
mCargoIntake = CargoIntake.getInstance();
mClimber = Climber.getInstance();
- mLED = LED.getInstance();
mSuperstructure = Superstructure.getInstance();
mRobotStateEstimator = RobotStateEstimator.getInstance();
+
mSubsystemManager = new SubsystemManager(
Arrays.asList(
mRobotStateEstimator,
@@ -112,7 +111,7 @@ public void robotInit()
mCargoChute,
mCargoIntake,
mClimber,
- mLED,
+ // mLED,
mSuperstructure));
mSubsystemManager.registerEnabledLoops(mEnabledLooper);
mSubsystemManager.registerDisabledLoops(mDisabledLooper);
diff --git a/src/main/java/com/spartronics4915/frc2019/VisionUpdateManager.java b/src/main/java/com/spartronics4915/frc2019/VisionUpdateManager.java
index 088e7fa..987f9ba 100644
--- a/src/main/java/com/spartronics4915/frc2019/VisionUpdateManager.java
+++ b/src/main/java/com/spartronics4915/frc2019/VisionUpdateManager.java
@@ -16,18 +16,21 @@
public class VisionUpdateManager
{
- public static VisionUpdateManager reverseVisionManager = new VisionUpdateManager("Reverse");
+
+ public static VisionUpdateManager reverseVisionManager = new VisionUpdateManager("Reverse", new Pose2d(-10, 0, Rotation2d.fromDegrees(180)));
private static final int kRawUpdateNumDoubles = 4; // 2 for x y, 1 for rotation, and 1 for processing time
- private final String kNetworkTablesKey;
+ private final String mNetworkTablesKey;
+ private final Pose2d mCameraOffset;
private VisionUpdate mLatestVisionUpdate = null;
- private VisionUpdateManager(String coprocessorID)
+ private VisionUpdateManager(String coprocessorID, Pose2d cameraOffset)
{
- kNetworkTablesKey = "/SmartDashboard/Vision/" + coprocessorID + "/solvePNP";
+ mNetworkTablesKey = "/SmartDashboard/Vision/" + coprocessorID + "/solvePNP";
+ mCameraOffset = cameraOffset;
- NetworkTableInstance.getDefault().addEntryListener(kNetworkTablesKey, (e) -> visionKeyChangedCallback(e),
+ NetworkTableInstance.getDefault().addEntryListener(mNetworkTablesKey, (e) -> visionKeyChangedCallback(e),
EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
}
@@ -35,8 +38,8 @@ private void visionKeyChangedCallback(EntryNotification entryNotification)
{
try
{
- String rawVisionUpdate = entryNotification.value.getString();
- mLatestVisionUpdate = VisionUpdate.fromRawUpdate(rawVisionUpdate);
+ double[] rawVisionUpdate = entryNotification.value.getDoubleArray();
+ mLatestVisionUpdate = VisionUpdate.fromRawUpdate(rawVisionUpdate, mCameraOffset);
}
catch (Exception e)
{
@@ -47,7 +50,7 @@ private void visionKeyChangedCallback(EntryNotification entryNotification)
}
/**
- * @return the latest vision update _or_ null if there has not been an update yet
+ * @return either empty or contains the latest vision update
*/
public Optional getLatestVisionUpdate()
{
@@ -58,73 +61,65 @@ public static class VisionUpdate
{
public final double frameCapturedTime; // Time in seconds where the epoch the boot of the RoboRIO (getFPGATimestamp's epoch)
- public final Pose2d targetRobotRelativePosition1; // The target's robot-relative position at frameCapturedTime (x and y in inches)
- public final Pose2d targetRobotRelativePosition2; // The target's robot-relative position at frameCapturedTime (x and y in inches)
+ public final Pose2d[] targetRobotRelativePositions; // The target's robot-relative position at frameCapturedTime (x and y in inches)
+ private final Pose2d mCameraOffset;
- private VisionUpdate(double capturedTime,
- Pose2d targetRelativePosition)
+ private VisionUpdate()
{
- this.frameCapturedTime = capturedTime;
- this.targetRobotRelativePosition1 = targetRelativePosition;
- this.targetRobotRelativePosition2 = null;
+ frameCapturedTime = 0;
+ mCameraOffset = null;
+ targetRobotRelativePositions = null;
}
- private VisionUpdate(double capturedTime, Pose2d pose1, Pose2d pose2)
+ private VisionUpdate(double capturedTime, Pose2d cameraOffset,
+ Pose2d... targetRelativePositions)
{
this.frameCapturedTime = capturedTime;
- this.targetRobotRelativePosition1 = pose1;
- this.targetRobotRelativePosition2 = pose2;
+ this.targetRobotRelativePositions = targetRelativePositions;
+
+ mCameraOffset = cameraOffset;
}
- public static VisionUpdate fromRawUpdate(String vu)
+ public static VisionUpdate fromRawUpdate(double[] values, Pose2d cameraOffset)
{
- String[] fields = vu.split(";"); // expect 2 or 3 fields
- int ntargets = fields.length - 1;
- if(ntargets <= 0)
- throw new RuntimeException("A vision update must have at least one target");
+ // a target is 3 numbers, we also expect one time, so
+ // the valid lengths are 1, 4, 7 => 0, 1, 2 targets
+ int len = values.length;
+ int ntargets = (len == 7) ? 2 : (len == 4) ? 1 : 0;
+ if (ntargets <= 0)
+ {
+ Logger.warning("A vision update must have at least one target");
+ return new VisionUpdate();
+ }
+
// last field is timestamp
- double frameCapTime = Double.parseDouble(fields[ntargets]);
- Pose2d pose1=null, pose2=null;
- for(int i=0;i mStartTime)
{
double now = Timer.getFPGATimestamp();
- mStateMap.reset(now, visionUpdate.getCorrectedRobotPose(0, kTargetLandmark, mStateMap, now));
+ mStateMap.reset(now, visionUpdate.getCorrectedRobotPose(kTargetLandmark, mStateMap, now));
mZeroed = true;
}
diff --git a/src/main/java/com/spartronics4915/frc2019/subsystems/LED.java b/src/main/java/com/spartronics4915/frc2019/subsystems/LED.java
deleted file mode 100644
index 675d6aa..0000000
--- a/src/main/java/com/spartronics4915/frc2019/subsystems/LED.java
+++ /dev/null
@@ -1,138 +0,0 @@
-package com.spartronics4915.frc2019.subsystems;
-
-import com.spartronics4915.lib.util.ILoop;
-import com.spartronics4915.lib.util.ILooper;
-
-public class LED extends Subsystem
-{
-
- private static LED mInstance = null;
-
- public static LED getInstance()
- {
- if (mInstance == null)
- {
- mInstance = new LED();
- }
- return mInstance;
- }
-
- public enum WantedState
- {
- CLOSED, INTAKE,
- }
-
- private enum SystemState
- {
- CLOSING, INTAKING,
- }
-
- private WantedState mWantedState = WantedState.CLOSED;
- private SystemState mSystemState = SystemState.CLOSING;
-
- private LED()
- {
- boolean success = true;
- try
- {
- // Instantiate your hardware here
- }
- catch (Exception e)
- {
- success = false;
- logException("Couldn't instantiate hardware", e);
- }
-
- logInitialized(success);
- }
-
- private final ILoop mLoop = new ILoop()
- {
-
- @Override
- public void onStart(double timestamp)
- {
- synchronized (LED.this)
- {
- mWantedState = WantedState.CLOSED;
- mSystemState = SystemState.CLOSING;
- }
- }
-
- @Override
- public void onLoop(double timestamp)
- {
- synchronized (LED.this)
- {
- SystemState newState = defaultStateTransfer();
- switch (mSystemState)
- {
- case INTAKING:
- break;
- case CLOSING:
- stop();
- break;
- default:
- logError("Unhandled system state!");
- }
- mSystemState = newState;
- }
- }
-
- @Override
- public void onStop(double timestamp)
- {
- synchronized (LED.this)
- {
- stop();
- }
- }
- };
-
- private SystemState defaultStateTransfer()
- {
- SystemState newState = mSystemState;
- switch (mWantedState)
- {
- case CLOSED:
- newState = SystemState.CLOSING;
- break;
- case INTAKE:
- newState = SystemState.INTAKING;
- break;
- default:
- newState = SystemState.CLOSING;
- break;
- }
- return newState;
- }
-
- public synchronized void setWantedState(WantedState wantedState)
- {
- mWantedState = wantedState;
- }
-
- @Override
- public void registerEnabledLoops(ILooper enabledLooper)
- {
- enabledLooper.register(mLoop);
- }
-
- @Override
- public boolean checkSystem(String variant)
- {
- return false;
- }
-
- @Override
- public void outputTelemetry()
- {
-
- }
-
- @Override
- public void stop()
- {
- // Stop your hardware here
- }
-}
diff --git a/src/main/java/com/spartronics4915/frc2019/subsystems/Superstructure.java b/src/main/java/com/spartronics4915/frc2019/subsystems/Superstructure.java
index deaddac..8bff862 100755
--- a/src/main/java/com/spartronics4915/frc2019/subsystems/Superstructure.java
+++ b/src/main/java/com/spartronics4915/frc2019/subsystems/Superstructure.java
@@ -234,7 +234,7 @@ public void onLoop(double timestamp)
Optional visionUpdate = VisionUpdateManager.reverseVisionManager.getLatestVisionUpdate();
mGotVisionUpdate = visionUpdate.isPresent();
- visionUpdate.ifPresent(v -> makeAndDrivePath(Constants.getRobotLengthCorrectedPose(v.getFieldPosition(0, mRobotStateMap)), true)); // TODO make not reversed
+ visionUpdate.ifPresent(v -> makeAndDrivePath(Constants.getRobotLengthCorrectedPose(v.getFieldPosition(mRobotStateMap)), true)); // TODO make not reversed
}
if (mDrive.isDoneWithTrajectory() && newState == mSystemState)
@@ -344,7 +344,7 @@ private void makeAndDrivePath(Pose2d goalPose, boolean reversed)
double startTime = Timer.getFPGATimestamp();
TrajectoryIterator> t =
new TrajectoryIterator<>((new TimedView<>((mTrajectoryGenerator.generateTrajectory(reversed, waypoints)))));
- // TODO: Maybe plug in our current velocity as the start veloicty of the path?
+ // TODO: Maybe plug in our current velocity as the start velocity of the path?
Logger.notice("Path generated; took " + (Timer.getFPGATimestamp() - startTime) + " seconds.");
mDrive.setTrajectory(t);