getMinAreaRectCorners() {
return minAreaRectCorners;
}
/**
* Return a list of the n corners in image space (origin top left, x right, y down), in no
* particular order, detected for this target.
*
* For fiducials, the order is known and is always counter-clock wise around the tag, like so:
*
*
* ⟶ +X 3 ----- 2
* | | |
* V | |
* +Y 0 ----- 1
*
*/
public List getDetectedCorners() {
return detectedCorners;
}
/**
* Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag
* space (X forward, Y left, Z up) with the lowest reprojection error
*/
public Transform3d getBestCameraToTarget() {
return bestCameraToTarget;
}
/**
* Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag
* space (X forward, Y left, Z up) with the highest reprojection error
*/
public Transform3d getAlternateCameraToTarget() {
return altCameraToTarget;
}
@Override
public int hashCode() {
final int prime = 31;
int result = 1;
long temp;
temp = Double.doubleToLongBits(yaw);
result = prime * result + (int) (temp ^ (temp >>> 32));
temp = Double.doubleToLongBits(pitch);
result = prime * result + (int) (temp ^ (temp >>> 32));
temp = Double.doubleToLongBits(area);
result = prime * result + (int) (temp ^ (temp >>> 32));
temp = Double.doubleToLongBits(skew);
result = prime * result + (int) (temp ^ (temp >>> 32));
result = prime * result + fiducialId;
result = prime * result + ((bestCameraToTarget == null) ? 0 : bestCameraToTarget.hashCode());
result = prime * result + ((altCameraToTarget == null) ? 0 : altCameraToTarget.hashCode());
temp = Double.doubleToLongBits(poseAmbiguity);
result = prime * result + (int) (temp ^ (temp >>> 32));
result = prime * result + ((minAreaRectCorners == null) ? 0 : minAreaRectCorners.hashCode());
result = prime * result + ((detectedCorners == null) ? 0 : detectedCorners.hashCode());
return result;
}
@Override
public boolean equals(Object obj) {
if (this == obj) return true;
if (obj == null) return false;
if (getClass() != obj.getClass()) return false;
PhotonTrackedTarget other = (PhotonTrackedTarget) obj;
if (Double.doubleToLongBits(yaw) != Double.doubleToLongBits(other.yaw)) return false;
if (Double.doubleToLongBits(pitch) != Double.doubleToLongBits(other.pitch)) return false;
if (Double.doubleToLongBits(area) != Double.doubleToLongBits(other.area)) return false;
if (Double.doubleToLongBits(skew) != Double.doubleToLongBits(other.skew)) return false;
if (fiducialId != other.fiducialId) return false;
if (bestCameraToTarget == null) {
if (other.bestCameraToTarget != null) return false;
} else if (!bestCameraToTarget.equals(other.bestCameraToTarget)) return false;
if (altCameraToTarget == null) {
if (other.altCameraToTarget != null) return false;
} else if (!altCameraToTarget.equals(other.altCameraToTarget)) return false;
if (Double.doubleToLongBits(poseAmbiguity) != Double.doubleToLongBits(other.poseAmbiguity))
return false;
if (minAreaRectCorners == null) {
if (other.minAreaRectCorners != null) return false;
} else if (!minAreaRectCorners.equals(other.minAreaRectCorners)) return false;
if (detectedCorners == null) {
if (other.detectedCorners != null) return false;
} else if (!detectedCorners.equals(other.detectedCorners)) return false;
return true;
}
@Override
public String toString() {
return "PhotonTrackedTarget{"
+ "yaw="
+ yaw
+ ", pitch="
+ pitch
+ ", area="
+ area
+ ", skew="
+ skew
+ ", fiducialId="
+ fiducialId
+ ", cameraToTarget="
+ bestCameraToTarget
+ ", targetCorners="
+ minAreaRectCorners
+ '}';
}
public static final class APacketSerde implements PacketSerde {
@Override
public int getMaxByteSize() {
return Double.BYTES * (5 + 7 + 2 * 4 + 1 + 7 + 2 * MAX_CORNERS);
}
@Override
public void pack(Packet packet, PhotonTrackedTarget value) {
packet.encode(value.yaw);
packet.encode(value.pitch);
packet.encode(value.area);
packet.encode(value.skew);
packet.encode(value.fiducialId);
if (value.fiducialId != -1) {
PacketUtils.packTransform3d(packet, value.bestCameraToTarget);
PacketUtils.packTransform3d(packet, value.altCameraToTarget);
packet.encode(value.poseAmbiguity);
}
for (int i = 0; i < 4; i++) {
TargetCorner.serde.pack(packet, value.minAreaRectCorners.get(i));
}
packet.encode((byte) Math.min(value.detectedCorners.size(), Byte.MAX_VALUE));
for (TargetCorner targetCorner : value.detectedCorners) {
TargetCorner.serde.pack(packet, targetCorner);
}
}
@Override
public PhotonTrackedTarget unpack(Packet packet) {
var yaw = packet.decodeDouble();
var pitch = packet.decodeDouble();
var area = packet.decodeDouble();
var skew = packet.decodeDouble();
var fiducialId = packet.decodeInt();
Transform3d best;
Transform3d alt;
double ambiguity;
if (fiducialId != -1.0) {
best = PacketUtils.unpackTransform3d(packet);
alt = PacketUtils.unpackTransform3d(packet);
ambiguity = packet.decodeDouble();
} else {
best = new Transform3d();
alt = new Transform3d();
ambiguity = -1.0;
}
var minAreaRectCorners = new ArrayList(4);
for (int i = 0; i < 4; i++) {
minAreaRectCorners.add(TargetCorner.serde.unpack(packet));
}
var len = packet.decodeByte();
var detectedCorners = new ArrayList(len);
for (int i = 0; i < len; i++) {
detectedCorners.add(TargetCorner.serde.unpack(packet));
}
return new PhotonTrackedTarget(
yaw,
pitch,
area,
skew,
fiducialId,
best,
alt,
ambiguity,
minAreaRectCorners,
detectedCorners);
}
}
public static final APacketSerde serde = new APacketSerde();
}