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. */ 025public class CameraTargetRelation { 026 public final Pose3d camPose; 027 public final Transform3d camToTarg; 028 public final double camToTargDist; 029 public final double camToTargDistXY; 030 public final Rotation2d camToTargYaw; 031 public final Rotation2d camToTargPitch; 032 033 /** Angle from the camera's relative x-axis */ 034 public final Rotation2d camToTargAngle; 035 036 public final Transform3d targToCam; 037 public final Rotation2d targToCamYaw; 038 public final Rotation2d targToCamPitch; 039 040 /** Angle from the target's relative x-axis */ 041 public final Rotation2d targToCamAngle; 042 043 public CameraTargetRelation(Pose3d cameraPose, Pose3d targetPose) { 044 this.camPose = cameraPose; 045 camToTarg = new Transform3d(cameraPose, targetPose); 046 camToTargDist = camToTarg.getTranslation().getNorm(); 047 camToTargDistXY = 048 Math.hypot(camToTarg.getTranslation().getX(), camToTarg.getTranslation().getY()); 049 camToTargYaw = new Rotation2d(camToTarg.getX(), camToTarg.getY()); 050 camToTargPitch = new Rotation2d(camToTargDistXY, -camToTarg.getZ()); 051 camToTargAngle = 052 new Rotation2d(Math.hypot(camToTargYaw.getRadians(), camToTargPitch.getRadians())); 053 targToCam = new Transform3d(targetPose, cameraPose); 054 targToCamYaw = new Rotation2d(targToCam.getX(), targToCam.getY()); 055 targToCamPitch = new Rotation2d(camToTargDistXY, -targToCam.getZ()); 056 targToCamAngle = 057 new Rotation2d(Math.hypot(targToCamYaw.getRadians(), targToCamPitch.getRadians())); 058 } 059}