Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Vision Lineup fixes #114

Merged
merged 3 commits into from
Feb 3, 2025
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
2 changes: 1 addition & 1 deletion gradle.properties
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
version=2025.1.6
version=2025.1.7

8 changes: 7 additions & 1 deletion vision/src/main/java/coppercore/vision/VisionIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform3d;
import org.littletonrobotics.junction.AutoLog;

/**
Expand Down Expand Up @@ -34,7 +35,12 @@ public static record PoseObservation(
double averageTagDistance) {}

public static record SingleTagObservation(
int tagId, double timestamp, double distance3D, Rotation2d tx, Rotation2d ty) {}
int tagId,
double timestamp,
double distance3D,
Transform3d cameraToTarget,
Rotation2d tx,
Rotation2d ty) {}
;

public default void updateInputs(VisionIOInputs inputs) {}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@ public void updateInputs(VisionIOInputs inputs) {
target.getFiducialId(),
result.getTimestampSeconds(),
target.getBestCameraToTarget().getTranslation().getNorm(),
target.getBestCameraToTarget(),
new Rotation2d(target.getYaw()),
new Rotation2d(target.getPitch())));
}
Expand Down Expand Up @@ -133,8 +134,9 @@ public void updateInputs(VisionIOInputs inputs) {
target.fiducialId,
result.getTimestampSeconds(),
target.getBestCameraToTarget().getTranslation().getNorm(),
new Rotation2d(target.getYaw()),
new Rotation2d(target.getPitch())));
target.getBestCameraToTarget(),
new Rotation2d(Math.toRadians(target.getYaw())),
new Rotation2d(Math.toRadians(target.getPitch()))));
}
}
}
Expand Down
4 changes: 2 additions & 2 deletions vision/src/main/java/coppercore/vision/VisionLocalizer.java
Original file line number Diff line number Diff line change
Expand Up @@ -130,10 +130,10 @@ public DistanceToTag getDistanceErrorToTag(
// calculate strafe and forward distances required to get to tag
double crossTrackDistance =
distanceXYPlane * Math.sin(tagObserved.tx().minus(new Rotation2d()).getRadians())
+ crossTrackOffsetMeters;
- crossTrackOffsetMeters;
double alongTrackDistance =
distanceXYPlane * Math.cos(tagObserved.tx().minus(new Rotation2d()).getRadians())
+ alongTrackOffsetMeters;
- alongTrackOffsetMeters;

return new DistanceToTag(crossTrackDistance, alongTrackDistance, true);
}
Expand Down
Loading