Skip to content

Commit

Permalink
Merge pull request #9 from Team334/vision-updates
Browse files Browse the repository at this point in the history
Vision updates
  • Loading branch information
PGgit08 authored Apr 5, 2024
2 parents 6ecb6c1 + 2f2eb08 commit 2d51d56
Show file tree
Hide file tree
Showing 6 changed files with 1,034 additions and 164 deletions.
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,11 @@
public final class Constants {
public static final Alliance SAFE_ALLIANCE = Alliance.Red;

public static class Limelights {
public static final String MAIN = "limelight-main";
public static final String INTAKE = "limelight-intake";
}

public static class CAN {
public static final int DRIVE_FRONT_LEFT = 1;
public static final int ROT_FRONT_LEFT = 2;
Expand Down
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,13 @@ public void robotInit() {
// for (int port = 5800; port <= 5807; port++) {
// PortForwarder.add(port, "limelight.local", port);
// }
PortForwarder.add(5800, "limelight.local", 5800);
PortForwarder.add(5801, "limelight.local", 5801);
PortForwarder.add(5805, "limelight.local", 5805);
PortForwarder.add(5800, "limelight-main.local", 5800);
PortForwarder.add(5801, "limelight-main.local", 5801);
PortForwarder.add(5805, "limelight-main.local", 5805);

// PortForwarder.add(5810, "limelight-intake.local", 5810);
// PortForwarder.add(5811, "limelight-intake.local", 5811);
// PortForwarder.add(5815, "limelight-intake.local", 5815);

// CameraServer.startAutomaticCapture(0);
UtilFuncs.LoadField();
Expand Down
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
import frc.robot.subsystems.IntakeSubsystem.FeedMode;
import frc.robot.subsystems.ShooterSubsystem.ShooterState;
import frc.robot.utils.UtilFuncs;
import frc.robot.utils.helpers.LimelightHelper.PoseEstimate;
import frc.robot.subsystems.LEDSubsystem;
import frc.robot.subsystems.ShooterSubsystem;
import frc.robot.subsystems.SwerveDriveSubsystem;
Expand Down Expand Up @@ -197,10 +198,10 @@ private void configureBindings() {

// TESTING ONLY!!!
_driveController.circle().onTrue(Commands.runOnce(() -> {
Optional<double[]> pose = _visionSubsystem.getBotposeBlue();
Optional<PoseEstimate> pose = _visionSubsystem.getBotposeBlue();

if (pose.isPresent()) {
Pose2d botpose = UtilFuncs.ToPose(pose.get());
Pose2d botpose = pose.get().pose;
_swerveSubsystem.resetPose(new Pose2d(botpose.getX(), botpose.getY(), _swerveSubsystem.getHeading()));
}
}, _swerveSubsystem));
Expand Down
54 changes: 25 additions & 29 deletions src/main/java/frc/robot/subsystems/SwerveDriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,13 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import frc.robot.Constants.FieldConstants;
import frc.robot.Constants.Limelights;
import frc.robot.Constants.PID;
import frc.robot.Constants.Speeds;
import frc.robot.utils.SwerveModule;
import frc.robot.utils.UtilFuncs;
import frc.robot.utils.helpers.LimelightHelper;
import frc.robot.utils.helpers.LimelightHelper.PoseEstimate;

/**
* @author Peter Gutkovich
Expand Down Expand Up @@ -98,7 +101,7 @@ Constants.Physical.SWERVE_KINEMATICS, getHeadingRaw(),
new SwerveModulePosition[] {_frontLeft.getPosition(), _frontRight.getPosition(), _backRight.getPosition(), _backLeft.getPosition()},
new Pose2d(),
VecBuilder.fill(0.03, 0.03, 0.01),
VecBuilder.fill(0.9, 0.9, 9999999)
VecBuilder.fill(0.4, 0.4, 9999999)
);

// OTHER POSSIBLE STD DEV VALUES:
Expand Down Expand Up @@ -211,39 +214,32 @@ private boolean updateBotpose() {
_backLeft.getPosition()
});

Optional<double[]> visionBotpose = _visionSubsystem.getBotposeBlue();
Optional<PoseEstimate> visionBotpose = _visionSubsystem.getBotposeBlue();

SmartDashboard.putBoolean("SEES TAG(S)", visionBotpose.isPresent());

// UPDATE BOTPOSE WITH VISION
if (visionBotpose.isPresent()) {
double[] llBotpose = visionBotpose.get();

double tagDistance = llBotpose[9];
double tagCount = llBotpose[7];

double xyStds = 0;
double yawStd = 9999999;

SmartDashboard.putNumber("TAG(S) DISTANCE", tagDistance);
SmartDashboard.putNumber("TAG COUNT", tagCount);

if (tagDistance <= FieldConstants.CLOSE_TAG_DISTANCE_THRESHOLD) {
if (tagCount >= 2) { xyStds = 0.25; yawStd = 9000; }
else { xyStds = 0.8; yawStd = 10000; }
}

else if (tagDistance <= FieldConstants.FAR_TAG_DISTANCE_THRESHOLD) {
if (tagCount >= 2) { xyStds = 0.9; yawStd = 13000; }
else { xyStds = 1.2; yawStd = 16000; }
}

else {
return false;
}

visionPublisher.set(UtilFuncs.ToPose(llBotpose));
_estimator.addVisionMeasurement(UtilFuncs.ToPose(llBotpose), _visionSubsystem.getLatency(), VecBuilder.fill(xyStds, xyStds, yawStd));
System.out.println("PRESENT");

LimelightHelper.SetRobotOrientation(
Limelights.MAIN,
getHeading().getDegrees(),
0,
0,
0,
0,
0
);

if (Math.abs(_gyro.getRate()) >= 500) return false;

visionPublisher.set(visionBotpose.get().pose);

_estimator.addVisionMeasurement(
visionBotpose.get().pose,
visionBotpose.get().timestampSeconds
);
}

return true;
Expand Down
65 changes: 10 additions & 55 deletions src/main/java/frc/robot/subsystems/VisionSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,24 +3,18 @@

import java.util.Optional;

import com.fasterxml.jackson.databind.JsonNode;
import com.fasterxml.jackson.databind.node.ArrayNode;

import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.Limelights;
import frc.robot.utils.helpers.LimelightHelper;
import frc.robot.utils.helpers.LimelightHelper.PoseEstimate;

/**
* @author Lucas Ou
* @author Alex Reyes
* @author Peter Gutkovich
*/
public class VisionSubsystem extends SubsystemBase {
private final LimelightHelper _main = new LimelightHelper("limelight-main");
private final LimelightHelper _intake = new LimelightHelper("limelight-intake");

/** Creates a new VisionSubsystem. */
public VisionSubsystem() {}

Expand All @@ -34,63 +28,29 @@ public void periodic() {
}
}

/**
* Returns the latency from the last time data was sent from the main limelight. This
* should be used in the pose estimator.
*/
public double getLatency() {
double tl = _main.getEntry("tl").getDouble(0);
double cl = _main.getEntry("cl").getDouble(0);

return Timer.getFPGATimestamp() - (tl / 1000.0) - (cl / 1000.0);
}

/** Return a boolean for whether a tag is seen by main cam. */
public boolean isApriltagVisible() {
double tv = _main.getEntry("tv").getDouble(0);

if (tv == 0) {
return false;
}

if (tv == 1) {
return true;
}

return false;
return LimelightHelper.getTV(Limelights.MAIN);
}

/** Return a boolean for whether a note is seen by intake cam. */
public boolean isNoteVisible() {
double tv = _intake.getEntry("tv").getDouble(0);

if (tv == 0) {
return false;
}

if (tv == 1) {
return true;
}

return false;
return LimelightHelper.getTV(Limelights.INTAKE);
}

/**
* Returns the NT "botpose_wpiblue" as an array from the limelight if tags are visible.
*
* @return NT "botpose_wpiblue" limelight topic.
* @return NT "botpose_wpiblue" limelight topic. This uses megatag 2.
*
* @see Optional
*/
public Optional<double[]> getBotposeBlue() {
public Optional<PoseEstimate> getBotposeBlue() {
if (!isApriltagVisible()) return Optional.empty();

NetworkTableEntry botpose_entry = _main.getEntry("botpose_wpiblue");
if (!botpose_entry.exists()) return Optional.empty();

double[] botpose_array = botpose_entry.getDoubleArray(new double[11]);
PoseEstimate botpose_blue = LimelightHelper.getBotPoseEstimate_wpiBlue_MegaTag2(Limelights.MAIN);

return Optional.of(botpose_array);
return Optional.of(botpose_blue);
}

/**
Expand All @@ -101,14 +61,9 @@ public Optional<double[]> getBotposeBlue() {
public Optional<double[]> getNoteAngles() {
if (!isNoteVisible()) return Optional.empty();

ArrayNode targets = _intake.getNeuralTargets();
JsonNode target = targets.get(0);

if (target == null) return Optional.empty();

double[] angles = {
target.get("tx").asDouble(0),
target.get("ty").asDouble(0)
LimelightHelper.getTX(Limelights.INTAKE),
LimelightHelper.getTY(Limelights.INTAKE)
};

return Optional.of(angles);
Expand Down
Loading

0 comments on commit 2d51d56

Please sign in to comment.