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.targeting;
019
020import edu.wpi.first.math.geometry.Transform3d;
021import edu.wpi.first.util.protobuf.ProtobufSerializable;
022import java.util.List;
023import org.photonvision.common.dataflow.structures.PacketSerde;
024import org.photonvision.struct.PhotonTrackedTargetSerde;
025import org.photonvision.targeting.proto.PhotonTrackedTargetProto;
026import org.photonvision.targeting.serde.PhotonStructSerializable;
027
028/** Information about a detected target. */
029public class PhotonTrackedTarget
030        implements ProtobufSerializable, PhotonStructSerializable<PhotonTrackedTarget> {
031    private static final int MAX_CORNERS = 8;
032
033    /** The yaw of the target in degrees, with left being the positive direction. */
034    public double yaw;
035
036    /** The pitch of the target in degrees, with up being the positive direction. */
037    public double pitch;
038
039    /** The area (how much of the camera feed the bounding box takes up) as a percentage (0-100). */
040    public double area;
041
042    /** The skew of the target in degrees, with counterclockwise being the positive direction. */
043    public double skew;
044
045    /** The fiducial ID, or -1 if it doesn't exist for this target. */
046    public int fiducialId;
047
048    /** The object detection class ID, or -1 if it doesn't exist for this target. */
049    public int objDetectId;
050
051    /** The object detection confidence, or -1 if it doesn't exist for this target. */
052    public float objDetectConf;
053
054    /** The transform with the lowest reprojection error */
055    public Transform3d bestCameraToTarget;
056
057    /** The transform with the highest reprojection error */
058    public Transform3d altCameraToTarget;
059
060    /** The ratio (best:alt) of reprojection errors */
061    public double poseAmbiguity;
062
063    /** Corners from the min-area rectangle bounding the target */
064    public List<TargetCorner> minAreaRectCorners;
065
066    /** Corners from the corner detection method used */
067    public List<TargetCorner> detectedCorners;
068
069    /**
070     * Construct a tracked target, given exactly 4 corners
071     *
072     * @param yaw The yaw of the target
073     * @param pitch The pitch of the target
074     * @param area The area of the target as a percentage of the camera image
075     * @param skew The skew of the target
076     * @param fiducialId The fiduical tag ID
077     * @param classId The object detection class ID
078     * @param objDetectConf The object detection confidence
079     * @param pose The best camera to target transform
080     * @param altPose The alternate camera to target transform
081     * @param ambiguity The ambiguity (best:alternate ratio of reprojection errors) of the target
082     * @param minAreaRectCorners The corners of minimum area bounding box of the target
083     * @param detectedCorners The detected corners of the target
084     */
085    public PhotonTrackedTarget(
086            double yaw,
087            double pitch,
088            double area,
089            double skew,
090            int fiducialId,
091            int classId,
092            float objDetectConf,
093            Transform3d pose,
094            Transform3d altPose,
095            double ambiguity,
096            List<TargetCorner> minAreaRectCorners,
097            List<TargetCorner> detectedCorners) {
098        assert minAreaRectCorners.size() == 4;
099
100        if (detectedCorners.size() > MAX_CORNERS) {
101            detectedCorners = detectedCorners.subList(0, MAX_CORNERS);
102        }
103
104        this.yaw = yaw;
105        this.pitch = pitch;
106        this.area = area;
107        this.skew = skew;
108        this.fiducialId = fiducialId;
109        this.objDetectId = classId;
110        this.objDetectConf = objDetectConf;
111        this.bestCameraToTarget = pose;
112        this.altCameraToTarget = altPose;
113        this.minAreaRectCorners = minAreaRectCorners;
114        this.detectedCorners = detectedCorners;
115        this.poseAmbiguity = ambiguity;
116    }
117
118    /** Used for serialization. */
119    public PhotonTrackedTarget() {}
120
121    public double getYaw() {
122        return yaw;
123    }
124
125    public double getPitch() {
126        return pitch;
127    }
128
129    /**
130     * The area (how much of the camera feed the bounding box takes up) as a percentage (0-100).
131     *
132     * @return The area as a percentage
133     */
134    public double getArea() {
135        return area;
136    }
137
138    public double getSkew() {
139        return skew;
140    }
141
142    /**
143     * Get the fiducial ID, or -1 if it doesn't exist for this target.
144     *
145     * @return The fiducial ID
146     */
147    public int getFiducialId() {
148        return fiducialId;
149    }
150
151    /**
152     * Get the object detection class ID number, or -1 if it doesn't exist for this target.
153     *
154     * @return The object detection class ID
155     */
156    public int getDetectedObjectClassID() {
157        return objDetectId;
158    }
159
160    /**
161     * Get the object detection confidence, or -1 if it doesn't exist for this target. This will be
162     * between 0 and 1, with 1 indicating most confidence, and 0 least.
163     *
164     * @return The object detection confidence
165     */
166    public float getDetectedObjectConfidence() {
167        return objDetectConf;
168    }
169
170    /**
171     * Get the ratio of best:alternate pose reprojection errors, called ambiguity. This is between 0
172     * and 1 (0 being no ambiguity, and 1 meaning both have the same reprojection error). Numbers
173     * above 0.2 are likely to be ambiguous. -1 if invalid.
174     *
175     * @return The pose ambiguity
176     */
177    public double getPoseAmbiguity() {
178        return poseAmbiguity;
179    }
180
181    /**
182     * Return a list of the 4 corners in image space (origin top left, x right, y down), in no
183     * particular order, of the minimum area bounding rectangle of this target
184     *
185     * @return The list of corners
186     */
187    public List<TargetCorner> getMinAreaRectCorners() {
188        return minAreaRectCorners;
189    }
190
191    /**
192     * Return a list of the n corners in image space (origin top left, x right, y down), in no
193     * particular order, detected for this target.
194     *
195     * <p>For fiducials, the order is known and is always counter-clock wise around the tag, like so:
196     *
197     * <pre>​
198     * ⟶ +X  3 ----- 2
199     * |      |       |
200     * V      |       |
201     * +Y     0 ----- 1
202     * </pre>
203     *
204     * @return The list of detected corners for this target
205     */
206    public List<TargetCorner> getDetectedCorners() {
207        return detectedCorners;
208    }
209
210    /**
211     * Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag
212     * space (X forward, Y left, Z up) with the lowest reprojection error
213     *
214     * @return The transform with the lowest reprojection error (the best)
215     */
216    public Transform3d getBestCameraToTarget() {
217        return bestCameraToTarget;
218    }
219
220    /**
221     * Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag
222     * space (X forward, Y left, Z up) with the highest reprojection error
223     *
224     * @return The transform with the highest reprojection error (the alternate)
225     */
226    public Transform3d getAlternateCameraToTarget() {
227        return altCameraToTarget;
228    }
229
230    @Override
231    public int hashCode() {
232        final int prime = 31;
233        int result = 1;
234        long temp;
235        temp = Double.doubleToLongBits(yaw);
236        result = prime * result + (int) (temp ^ (temp >>> 32));
237        temp = Double.doubleToLongBits(pitch);
238        result = prime * result + (int) (temp ^ (temp >>> 32));
239        temp = Double.doubleToLongBits(area);
240        result = prime * result + (int) (temp ^ (temp >>> 32));
241        temp = Double.doubleToLongBits(skew);
242        result = prime * result + (int) (temp ^ (temp >>> 32));
243        result = prime * result + fiducialId;
244        result = prime * result + objDetectId;
245        result = prime * result + Float.floatToIntBits(objDetectConf);
246        result = prime * result + ((bestCameraToTarget == null) ? 0 : bestCameraToTarget.hashCode());
247        result = prime * result + ((altCameraToTarget == null) ? 0 : altCameraToTarget.hashCode());
248        temp = Double.doubleToLongBits(poseAmbiguity);
249        result = prime * result + (int) (temp ^ (temp >>> 32));
250        result = prime * result + ((minAreaRectCorners == null) ? 0 : minAreaRectCorners.hashCode());
251        result = prime * result + ((detectedCorners == null) ? 0 : detectedCorners.hashCode());
252        return result;
253    }
254
255    @Override
256    public boolean equals(Object obj) {
257        if (this == obj) return true;
258        if (obj == null) return false;
259        if (getClass() != obj.getClass()) return false;
260        PhotonTrackedTarget other = (PhotonTrackedTarget) obj;
261        if (Double.doubleToLongBits(yaw) != Double.doubleToLongBits(other.yaw)) return false;
262        if (Double.doubleToLongBits(pitch) != Double.doubleToLongBits(other.pitch)) return false;
263        if (Double.doubleToLongBits(area) != Double.doubleToLongBits(other.area)) return false;
264        if (Double.doubleToLongBits(skew) != Double.doubleToLongBits(other.skew)) return false;
265        if (fiducialId != other.fiducialId) return false;
266        if (objDetectId != other.objDetectId) return false;
267        if (Float.floatToIntBits(objDetectConf) != Float.floatToIntBits(other.objDetectConf))
268            return false;
269        if (bestCameraToTarget == null) {
270            if (other.bestCameraToTarget != null) return false;
271        } else if (!bestCameraToTarget.equals(other.bestCameraToTarget)) return false;
272        if (altCameraToTarget == null) {
273            if (other.altCameraToTarget != null) return false;
274        } else if (!altCameraToTarget.equals(other.altCameraToTarget)) return false;
275        if (Double.doubleToLongBits(poseAmbiguity) != Double.doubleToLongBits(other.poseAmbiguity))
276            return false;
277        if (minAreaRectCorners == null) {
278            if (other.minAreaRectCorners != null) return false;
279        } else if (!minAreaRectCorners.equals(other.minAreaRectCorners)) return false;
280        if (detectedCorners == null) {
281            if (other.detectedCorners != null) return false;
282        } else if (!detectedCorners.equals(other.detectedCorners)) return false;
283        return true;
284    }
285
286    @Override
287    public String toString() {
288        return "PhotonTrackedTarget [yaw="
289                + yaw
290                + ", pitch="
291                + pitch
292                + ", area="
293                + area
294                + ", skew="
295                + skew
296                + ", fiducialId="
297                + fiducialId
298                + ", objDetectId="
299                + objDetectId
300                + ", objDetectConf="
301                + objDetectConf
302                + ", bestCameraToTarget="
303                + bestCameraToTarget
304                + ", altCameraToTarget="
305                + altCameraToTarget
306                + ", poseAmbiguity="
307                + poseAmbiguity
308                + ", minAreaRectCorners="
309                + minAreaRectCorners
310                + ", detectedCorners="
311                + detectedCorners
312                + "]";
313    }
314
315    /** PhotonTrackedTarget protobuf for serialization. */
316    public static final PhotonTrackedTargetProto proto = new PhotonTrackedTargetProto();
317
318    /** PhotonTrackedTarget PhotonStruct for serialization. */
319    public static final PhotonTrackedTargetSerde photonStruct = new PhotonTrackedTargetSerde();
320
321    @Override
322    public PacketSerde<PhotonTrackedTarget> getSerde() {
323        return photonStruct;
324    }
325}