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.Rotation3d;
023import edu.wpi.first.math.geometry.Translation3d;
024import edu.wpi.first.math.util.Units;
025import java.util.ArrayList;
026import java.util.List;
027import java.util.stream.Collectors;
028
029/** Describes the 3d model of a target. */
030public class TargetModel {
031    /**
032     * Translations of this target's vertices relative to its pose. Rectangular and spherical targets
033     * will have four vertices. See their respective constructors for more info.
034     */
035    public final List<Translation3d> vertices;
036
037    public final boolean isPlanar;
038    public final boolean isSpherical;
039
040    public static final TargetModel kAprilTag16h5 =
041            new TargetModel(Units.inchesToMeters(6), Units.inchesToMeters(6));
042    public static final TargetModel kAprilTag36h11 =
043            new TargetModel(Units.inchesToMeters(6.5), Units.inchesToMeters(6.5));
044
045    /**
046     * Creates a rectangular, planar target model given the width and height. The model has four
047     * vertices:
048     *
049     * <ul>
050     *   <li>Point 0: [0, -width/2, -height/2]
051     *   <li>Point 1: [0, width/2, -height/2]
052     *   <li>Point 2: [0, width/2, height/2]
053     *   <li>Point 3: [0, -width/2, height/2]
054     * </ul>
055     */
056    public TargetModel(double widthMeters, double heightMeters) {
057        this.vertices =
058                List.of(
059                        // this order is relevant for AprilTag compatibility
060                        new Translation3d(0, -widthMeters / 2.0, -heightMeters / 2.0),
061                        new Translation3d(0, widthMeters / 2.0, -heightMeters / 2.0),
062                        new Translation3d(0, widthMeters / 2.0, heightMeters / 2.0),
063                        new Translation3d(0, -widthMeters / 2.0, heightMeters / 2.0));
064        this.isPlanar = true;
065        this.isSpherical = false;
066    }
067
068    /**
069     * Creates a cuboid target model given the length, width, height. The model has eight vertices:
070     *
071     * <ul>
072     *   <li>Point 0: [length/2, -width/2, -height/2]
073     *   <li>Point 1: [length/2, width/2, -height/2]
074     *   <li>Point 2: [length/2, width/2, height/2]
075     *   <li>Point 3: [length/2, -width/2, height/2]
076     *   <li>Point 4: [-length/2, -width/2, height/2]
077     *   <li>Point 5: [-length/2, width/2, height/2]
078     *   <li>Point 6: [-length/2, width/2, -height/2]
079     *   <li>Point 7: [-length/2, -width/2, -height/2]
080     * </ul>
081     */
082    public TargetModel(double lengthMeters, double widthMeters, double heightMeters) {
083        this(
084                List.of(
085                        new Translation3d(lengthMeters / 2.0, -widthMeters / 2.0, -heightMeters / 2.0),
086                        new Translation3d(lengthMeters / 2.0, widthMeters / 2.0, -heightMeters / 2.0),
087                        new Translation3d(lengthMeters / 2.0, widthMeters / 2.0, heightMeters / 2.0),
088                        new Translation3d(lengthMeters / 2.0, -widthMeters / 2.0, heightMeters / 2.0),
089                        new Translation3d(-lengthMeters / 2.0, -widthMeters / 2.0, heightMeters / 2.0),
090                        new Translation3d(-lengthMeters / 2.0, widthMeters / 2.0, heightMeters / 2.0),
091                        new Translation3d(-lengthMeters / 2.0, widthMeters / 2.0, -heightMeters / 2.0),
092                        new Translation3d(-lengthMeters / 2.0, -widthMeters / 2.0, -heightMeters / 2.0)));
093    }
094
095    /**
096     * Creates a spherical target model which has similar dimensions regardless of its rotation. This
097     * model has four vertices:
098     *
099     * <ul>
100     *   <li>Point 0: [0, -radius, 0]
101     *   <li>Point 1: [0, 0, -radius]
102     *   <li>Point 2: [0, radius, 0]
103     *   <li>Point 3: [0, 0, radius]
104     * </ul>
105     *
106     * <i>Q: Why these vertices?</i> A: This target should be oriented to the camera every frame, much
107     * like a sprite/decal, and these vertices represent the ellipse vertices (maxima). These vertices
108     * are used for drawing the image of this sphere, but do not match the corners that will be
109     * published by photonvision.
110     */
111    public TargetModel(double diameterMeters) {
112        double radius = diameterMeters / 2.0;
113        this.vertices =
114                List.of(
115                        new Translation3d(0, -radius, 0),
116                        new Translation3d(0, 0, -radius),
117                        new Translation3d(0, radius, 0),
118                        new Translation3d(0, 0, radius));
119        this.isPlanar = false;
120        this.isSpherical = true;
121    }
122
123    /**
124     * Creates a target model from arbitrary 3d vertices. Automatically determines if the given
125     * vertices are planar(x == 0). More than 2 vertices must be given. If this is a planar model, the
126     * vertices should define a non-intersecting contour.
127     *
128     * @param vertices Translations representing the vertices of this target model relative to its
129     *     pose.
130     */
131    public TargetModel(List<Translation3d> vertices) {
132        this.isSpherical = false;
133        if (vertices == null || vertices.size() <= 2) {
134            vertices = new ArrayList<>();
135            this.isPlanar = false;
136        } else {
137            boolean cornersPlanar = true;
138            for (Translation3d corner : vertices) {
139                if (corner.getX() != 0) cornersPlanar = false;
140            }
141            this.isPlanar = cornersPlanar;
142        }
143        this.vertices = vertices;
144    }
145
146    /**
147     * This target's vertices offset from its field pose.
148     *
149     * <p>Note: If this target is spherical, use {@link #getOrientedPose(Translation3d,
150     * Translation3d)} with this method.
151     */
152    public List<Translation3d> getFieldVertices(Pose3d targetPose) {
153        var basisChange = new RotTrlTransform3d(targetPose.getRotation(), targetPose.getTranslation());
154        return vertices.stream().map(basisChange::apply).collect(Collectors.toList());
155    }
156
157    /**
158     * Returns a Pose3d with the given target translation oriented (with its relative x-axis aligned)
159     * to the camera translation. This is used for spherical targets which should not have their
160     * projection change regardless of their own rotation.
161     *
162     * @param tgtTrl This target's translation
163     * @param cameraTrl Camera's translation
164     * @return This target's pose oriented to the camera
165     */
166    public static Pose3d getOrientedPose(Translation3d tgtTrl, Translation3d cameraTrl) {
167        var relCam = cameraTrl.minus(tgtTrl);
168        var orientToCam =
169                new Rotation3d(
170                        0,
171                        new Rotation2d(Math.hypot(relCam.getX(), relCam.getY()), -relCam.getZ()).getRadians(),
172                        new Rotation2d(relCam.getX(), relCam.getY()).getRadians());
173        return new Pose3d(tgtTrl, orientToCam);
174    }
175
176    @Override
177    public boolean equals(Object obj) {
178        return this == obj
179                && obj instanceof TargetModel o
180                && vertices.equals(o.vertices)
181                && isPlanar == o.isPlanar
182                && isSpherical == o.isSpherical;
183    }
184}