Skip to content

Commit

Permalink
Limelights now return WPI botposes
Browse files Browse the repository at this point in the history
Alliance should automatically be correct

--Gabe
  • Loading branch information
willitcode committed Oct 31, 2023
1 parent edaa485 commit decc1b7
Showing 1 changed file with 13 additions and 4 deletions.
17 changes: 13 additions & 4 deletions src/main/java/frc/robot/subsystems/Limelight.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@
import edu.wpi.first.networktables.DoubleArraySubscriber;
import edu.wpi.first.networktables.DoubleSubscriber;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.positioning.Pose;

Expand Down Expand Up @@ -56,10 +58,17 @@ public Limelight(String name) {
txSubscriber = NetworkTableInstance.getDefault().getDoubleTopic(fmtPath("tx")).subscribe(0.0);
tySubscriber = NetworkTableInstance.getDefault().getDoubleTopic(fmtPath("ty")).subscribe(0.0);
taSubscriber = NetworkTableInstance.getDefault().getDoubleTopic(fmtPath("ta")).subscribe(0.0);
botposSubscriber =
NetworkTableInstance.getDefault()
.getDoubleArrayTopic(fmtPath("botpose"))
.subscribe(new double[] {0.0, 0.0, 0.0, 0.0, 0.0, 0.0});
if (DriverStation.getAlliance() == Alliance.Blue) {
botposSubscriber =
NetworkTableInstance.getDefault()
.getDoubleArrayTopic(fmtPath("botpose_wpiblue"))
.subscribe(new double[] {0.0, 0.0, 0.0, 0.0, 0.0, 0.0});
} else {
botposSubscriber =
NetworkTableInstance.getDefault()
.getDoubleArrayTopic(fmtPath("botpose_wpired"))
.subscribe(new double[] {0.0, 0.0, 0.0, 0.0, 0.0, 0.0});
}
}

/* now its time for getter method chaingun, which I have to write manually because VS Code */
Expand Down

0 comments on commit decc1b7

Please sign in to comment.