001/* 002 * Copyright (C) Photon Vision. 003 * 004 * This program is free software: you can redistribute it and/or modify 005 * it under the terms of the GNU General Public License as published by 006 * the Free Software Foundation, either version 3 of the License, or 007 * (at your option) any later version. 008 * 009 * This program is distributed in the hope that it will be useful, 010 * but WITHOUT ANY WARRANTY; without even the implied warranty of 011 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 012 * GNU General Public License for more details. 013 * 014 * You should have received a copy of the GNU General Public License 015 * along with this program. If not, see <https://www.gnu.org/licenses/>. 016 */ 017 018package org.photonvision.estimation; 019 020import edu.wpi.first.math.geometry.Pose3d; 021import edu.wpi.first.math.geometry.Rotation2d; 022import edu.wpi.first.math.geometry.Transform3d; 023 024/** Holds various helper geometries describing the relation between camera and target. */ 025@SuppressWarnings("doclint") 026public class CameraTargetRelation { 027 public final Pose3d camPose; 028 public final Transform3d camToTarg; 029 public final double camToTargDist; 030 public final double camToTargDistXY; 031 public final Rotation2d camToTargYaw; 032 public final Rotation2d camToTargPitch; 033 034 /** Angle from the camera's relative x-axis */ 035 public final Rotation2d camToTargAngle; 036 037 public final Transform3d targToCam; 038 public final Rotation2d targToCamYaw; 039 public final Rotation2d targToCamPitch; 040 041 /** Angle from the target's relative x-axis */ 042 public final Rotation2d targToCamAngle; 043 044 public CameraTargetRelation(Pose3d cameraPose, Pose3d targetPose) { 045 this.camPose = cameraPose; 046 camToTarg = new Transform3d(cameraPose, targetPose); 047 camToTargDist = camToTarg.getTranslation().getNorm(); 048 camToTargDistXY = 049 Math.hypot(camToTarg.getTranslation().getX(), camToTarg.getTranslation().getY()); 050 camToTargYaw = new Rotation2d(camToTarg.getX(), camToTarg.getY()); 051 camToTargPitch = new Rotation2d(camToTargDistXY, -camToTarg.getZ()); 052 camToTargAngle = 053 new Rotation2d(Math.hypot(camToTargYaw.getRadians(), camToTargPitch.getRadians())); 054 targToCam = new Transform3d(targetPose, cameraPose); 055 targToCamYaw = new Rotation2d(targToCam.getX(), targToCam.getY()); 056 targToCamPitch = new Rotation2d(camToTargDistXY, -targToCam.getZ()); 057 targToCamAngle = 058 new Rotation2d(Math.hypot(targToCamYaw.getRadians(), targToCamPitch.getRadians())); 059 } 060}