Skip to content

Commit

Permalink
Format
Browse files Browse the repository at this point in the history
  • Loading branch information
simonstoryparker committed Nov 26, 2024
1 parent e175784 commit 0aef558
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 25 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/vision/Limelight.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ public class Limelight {

private final Timer limelightTimer = new Timer();

public Limelight(String name, Pose3d robotRelativePose, CameraDataset interpolationData) {
public Limelight(String name, CameraDataset interpolationData) {
limelightTableName = "limelight-" + name;
this.name = name;
this.interpolationData = interpolationData;
Expand Down
53 changes: 29 additions & 24 deletions src/main/java/frc/robot/vision/VisionSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,8 @@ public class VisionSubsystem extends StateMachine<VisionState> {
private double rollRate;

// right is positive x, up is positive y, forward is positive z
private final Pose3d robotPoseCalibrationTargetSpaceMetersRadians = new Pose3d(0, -1.0, -1.5, new Rotation3d(0.0, 0.0, 0.0));
private final Pose3d robotPoseCalibrationTargetSpaceMetersRadians =
new Pose3d(0, -1.0, -1.5, new Rotation3d(0.0, 0.0, 0.0));

public static final Pose2d ORIGINAL_RED_SPEAKER =
new Pose2d(
Expand Down Expand Up @@ -80,9 +81,12 @@ private void logCalibrationValues() {
var leftCameraPoseTargetSpace = LimelightHelpers.getCameraPose3d_TargetSpace("limelight");
var rightCameraPoseTargetSpace = LimelightHelpers.getCameraPose3d_TargetSpace("limelight");

var leftCameraRobotRelativePose = getRobotRelativeCameraOffset(robotPoseCalibrationTargetSpaceMetersRadians,
leftCameraPoseTargetSpace);
var rightCameraRobotRelativePose = getRobotRelativeCameraOffset(robotPoseCalibrationTargetSpaceMetersRadians, rightCameraPoseTargetSpace);
var leftCameraRobotRelativePose =
getRobotRelativeCameraOffset(
robotPoseCalibrationTargetSpaceMetersRadians, leftCameraPoseTargetSpace);
var rightCameraRobotRelativePose =
getRobotRelativeCameraOffset(
robotPoseCalibrationTargetSpaceMetersRadians, rightCameraPoseTargetSpace);

DogLog.log("Calibration/LeftCamera/Right", leftCameraRobotRelativePose.getX());
DogLog.log("Calibration/LeftCamera/Up", leftCameraRobotRelativePose.getY());
Expand All @@ -99,26 +103,27 @@ private void logCalibrationValues() {
DogLog.log("Calibration/RightCamera/Yaw", rightCameraRobotRelativePose.getRotation().getZ());
}

private Pose3d getRobotRelativeCameraOffset(Pose3d robotPoseTargetSpace, Pose3d seenCameraPoseTargetSpace) {
// Positive X = Right
var cameraLeftRight = seenCameraPoseTargetSpace.getX();
// Positive Y = Down, so flipped for common sense
var cameraUpDown = -1 * (seenCameraPoseTargetSpace.getY());
// Positive Z = Backward, so flipped for common sense
var cameraForwardBackward = -1 * (seenCameraPoseTargetSpace.getZ());
// Pitch rotates around left right axis (x according to LL coordinate systems)
var cameraPitch = Units.degreesToRadians(seenCameraPoseTargetSpace.getRotation().getX());
// Roll rotates around forward backward axis (Z according to LL coordinate systems)
var cameraRoll = Units.degreesToRadians(seenCameraPoseTargetSpace.getRotation().getZ());
// Yaw rotates around up down axis (y according to LL coordinate systems)
var cameraYaw = Units.degreesToRadians(seenCameraPoseTargetSpace.getRotation().getY());

var robotLeftRight = robotPoseTargetSpace.getX();
var robotUpDown = robotPoseTargetSpace.getY();
var robotForwardBackward = robotPoseTargetSpace.getZ();
var robotPitch = robotPoseTargetSpace.getRotation().getY();
var robotRoll = robotPoseTargetSpace.getRotation().getX();
var robotYaw = robotPoseTargetSpace.getRotation().getZ();
private Pose3d getRobotRelativeCameraOffset(
Pose3d robotPoseTargetSpace, Pose3d seenCameraPoseTargetSpace) {
// Positive X = Right
var cameraLeftRight = seenCameraPoseTargetSpace.getX();
// Positive Y = Down, so flipped for common sense
var cameraUpDown = -1 * (seenCameraPoseTargetSpace.getY());
// Positive Z = Backward, so flipped for common sense
var cameraForwardBackward = -1 * (seenCameraPoseTargetSpace.getZ());
// Pitch rotates around left right axis (x according to LL coordinate systems)
var cameraPitch = Units.degreesToRadians(seenCameraPoseTargetSpace.getRotation().getX());
// Roll rotates around forward backward axis (Z according to LL coordinate systems)
var cameraRoll = Units.degreesToRadians(seenCameraPoseTargetSpace.getRotation().getZ());
// Yaw rotates around up down axis (y according to LL coordinate systems)
var cameraYaw = Units.degreesToRadians(seenCameraPoseTargetSpace.getRotation().getY());

var robotLeftRight = robotPoseTargetSpace.getX();
var robotUpDown = robotPoseTargetSpace.getY();
var robotForwardBackward = robotPoseTargetSpace.getZ();
var robotPitch = robotPoseTargetSpace.getRotation().getY();
var robotRoll = robotPoseTargetSpace.getRotation().getX();
var robotYaw = robotPoseTargetSpace.getRotation().getZ();

var right = cameraLeftRight - robotLeftRight;
var up = cameraUpDown - robotUpDown;
Expand Down

0 comments on commit 0aef558

Please sign in to comment.