diff --git a/build.gradle b/build.gradle index 0f8a20e27e..0f3ad85f24 100644 --- a/build.gradle +++ b/build.gradle @@ -6,7 +6,7 @@ plugins { id "edu.wpi.first.wpilib.repositories.WPILibRepositoriesPlugin" version "2020.2" id "edu.wpi.first.GradleRIO" version "2025.3.2" id 'edu.wpi.first.WpilibTools' version '1.3.0' - id 'com.google.protobuf' version '0.9.3' apply false + id 'com.google.protobuf' version '0.9.5' apply false id 'edu.wpi.first.GradleJni' version '1.1.0' id "org.ysb33r.doxygen" version "1.0.4" apply false id 'com.gradleup.shadow' version '8.3.4' apply false diff --git a/docs/source/docs/contributing/design-descriptions/index.md b/docs/source/docs/contributing/design-descriptions/index.md index b6e706271a..644655f7ba 100644 --- a/docs/source/docs/contributing/design-descriptions/index.md +++ b/docs/source/docs/contributing/design-descriptions/index.md @@ -6,4 +6,5 @@ image-rotation time-sync camera-matching e2e-latency +tag-limiting ``` diff --git a/docs/source/docs/contributing/design-descriptions/tag-limiting.md b/docs/source/docs/contributing/design-descriptions/tag-limiting.md new file mode 100644 index 0000000000..b0a46b3d02 --- /dev/null +++ b/docs/source/docs/contributing/design-descriptions/tag-limiting.md @@ -0,0 +1,21 @@ +# AprilTag Rejection + +With the introduction of AprilTag's and full field localisation becoming more common rejecting tags that aren't relevant to the robot has become more important for maintaining a useful pose estimation. Including tags that aren't relevant to your objective can harm localisation, causing results to become more noisy and eventually skewed over the course of an event. In order to prevent this we can reject tags that aren't related to our current objective. There are a couple of things to consider when it comes to rejecting tags: +- why can't this be done in user code +- accessing rejected tag info +- synchronisation between coprocessor and robot code + +## Why not do this in user code? + +The first thing that may come to mind when talking about tag rejection is, why not just do this in user code? After all we provide the tag IDs to the user. The main issue with doing this in user code is it means that you have to reject entire multitag results, when in reality you still want a multitag estimate just without the rejected tag. One way to work around this would be running all pose estimations in user code but this is a significant performance to robot code, particularly on the roboRIO. + +## Accessing rejected tag info + +Accessing rejected tag info is still important, as tags can serve other information not just localisation. For example in the 2025-2026 FTC Game, Decode, there was a tag utilised to determine different patterns of scoring elements. Mechanisms like this make it desirable to still have access to detection info even when we reject a tag for localisation purposes. + +## Synchronisation between coprocessor and robot code + +In order to be able to use Photon standalone without any robot code we must be able to change the tags to reject on the coprocessor. This unfortunately doesn't scale well with more complex robot code usecases, for example rejecting tags based on current scoring location or alliance, making it beneficial to be able to set the tags to reject from robot code as well. This raises a couple of questions: +- How do we keep the coprocessor and robot code in sync? +- What do we do if the robot code and coprocessor have conflicting values? +The core of our approach to this will be always treating the robot code as a source of truth. If the robot code is publishing values for this then you won't be able to modify the values in the UI. Publishing from the UI will still be enabled when the robot code isn't publishing, but if you've set a value in the user code it will always override the value set on the coprocessor. If the value is ever overriden an Alert will be published. Furthermore if the robot code stops publishing it will return to the value set on the coprocessor. diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java index 9498561956..106418386c 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java @@ -160,7 +160,8 @@ public void accept(CVPipelineResult result) { now + offset, NetworkTablesManager.getInstance().getTimeSinceLastPong(), TrackedTarget.simpleFromTrackedTargets(acceptedResult.targets), - acceptedResult.multiTagResult); + acceptedResult.multiTagResult, + acceptedResult.rejectedTags); // random guess at size of the array ts.resultPublisher.set(simplified, 1024); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java index 3e98f7e9e1..36056af5f3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java @@ -140,10 +140,21 @@ protected CVPipelineResult process(Frame frame, AprilTagPipelineSettings setting List detections = tagDetectionPipeResult.output; List usedDetections = new ArrayList<>(); + List rejectedTags = new ArrayList<>(); List targetList = new ArrayList<>(); // Filter out detections based on pipeline settings for (AprilTagDetection detection : detections) { + if (settings.rejectTagIds.contains(detection.getId())) { + TrackedTarget target = + new TrackedTarget( + detection, + null, + new TargetCalculationParameters( + false, null, null, null, null, frameStaticProperties)); + rejectedTags.add(target); + continue; + } // TODO this should be in a pipe, not in the top level here (Matt) if (detection.getDecisionMargin() < settings.decisionMargin) continue; if (detection.getHamming() > settings.hammingDist) continue; @@ -236,7 +247,13 @@ protected CVPipelineResult process(Frame frame, AprilTagPipelineSettings setting var fps = fpsResult.output; return new CVPipelineResult( - frame.sequenceID, sumPipeNanosElapsed, fps, targetList, multiTagResult, frame); + frame.sequenceID, + sumPipeNanosElapsed, + fps, + targetList, + multiTagResult, + frame, + rejectedTags); } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java index cede417e23..da6ee6b096 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java @@ -18,6 +18,7 @@ package org.photonvision.vision.pipeline; import com.fasterxml.jackson.annotation.JsonTypeName; +import java.util.List; import org.photonvision.vision.apriltag.AprilTagFamily; import org.photonvision.vision.target.TargetModel; @@ -34,8 +35,7 @@ public class AprilTagPipelineSettings extends AdvancedPipelineSettings { public int decisionMargin = 35; public boolean doMultiTarget = false; public boolean doSingleTargetAlways = false; - - // 3d settings + public List rejectedTagIds = List.of(); public AprilTagPipelineSettings() { super(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java index 51773c9f16..4198b258ad 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java @@ -34,6 +34,7 @@ public class CVPipelineResult implements Releasable { public final List targets; public final Frame inputAndOutputFrame; public Optional multiTagResult; + public final Optional> rejectedTags; public final List objectDetectionClassNames; public CVPipelineResult( @@ -72,13 +73,15 @@ public CVPipelineResult( List targets, Optional multiTagResult, Frame inputFrame, - List classNames) { + List classNames, + List rejectedTags) { this.sequenceID = sequenceID; this.processingNanos = processingNanos; this.fps = fps; this.targets = targets != null ? targets : Collections.emptyList(); this.multiTagResult = multiTagResult; this.objectDetectionClassNames = classNames; + this.rejectedTags = rejectedTags; this.inputAndOutputFrame = inputFrame; } diff --git a/photon-lib/py/photonlibpy/generated/PhotonPipelineResultSerde.py b/photon-lib/py/photonlibpy/generated/PhotonPipelineResultSerde.py index 885ce2c963..0d46ca81e2 100644 --- a/photon-lib/py/photonlibpy/generated/PhotonPipelineResultSerde.py +++ b/photon-lib/py/photonlibpy/generated/PhotonPipelineResultSerde.py @@ -41,8 +41,8 @@ class PhotonPipelineResultSerde: # Message definition md5sum. See photon_packet.adoc for details - MESSAGE_VERSION = "4b2ff16a964b5e2bf04be0c1454d91c4" - MESSAGE_FORMAT = "PhotonPipelineMetadata:ac0a45f686457856fb30af77699ea356 metadata;PhotonTrackedTarget:cc6dbb5c5c1e0fa808108019b20863f1 targets[?];optional MultiTargetPNPResult:541096947e9f3ca2d3f425ff7b04aa7b multitagResult;" + MESSAGE_VERSION = "29e82c187da35e0337c86f4c14ee5ac7" + MESSAGE_FORMAT = "PhotonPipelineMetadata:ac0a45f686457856fb30af77699ea356 metadata;PhotonTrackedTarget:cc6dbb5c5c1e0fa808108019b20863f1 targets[?];optional MultiTargetPNPResult:541096947e9f3ca2d3f425ff7b04aa7b multitagResult;optional PhotonTrackedTarget:cc6dbb5c5c1e0fa808108019b20863f1 rejectedTags[?];" @staticmethod def pack(value: "PhotonPipelineResult") -> "Packet": @@ -56,6 +56,9 @@ def pack(value: "PhotonPipelineResult") -> "Packet": # multitagResult is optional! it better not be a VLA too ret.encodeOptional(value.multitagResult, MultiTargetPNPResult.photonStruct) + + # rejectedTags is optional! it better not be a VLA too + ret.encodeOptional(value.rejectedTags, PhotonTrackedTarget.photonStruct) return ret @staticmethod @@ -71,6 +74,9 @@ def unpack(packet: "Packet") -> "PhotonPipelineResult": # multitagResult is optional! it better not be a VLA too ret.multitagResult = packet.decodeOptional(MultiTargetPNPResult.photonStruct) + # rejectedTags is optional! it better not be a VLA too + ret.rejectedTags = packet.decodeOptional(PhotonTrackedTarget.photonStruct) + return ret diff --git a/photon-serde/generate_messages.py b/photon-serde/generate_messages.py old mode 100644 new mode 100755 index 2efca52812..6ce345f06f --- a/photon-serde/generate_messages.py +++ b/photon-serde/generate_messages.py @@ -218,14 +218,6 @@ def get_struct_schema_str(message: MessageType, message_db: List[MessageType]): ret = "" for field in message["fields"]: - if ( - "optional" in field - and field["optional"] == True - and "vla" in field - and field["vla"] == True - ): - raise Exception(f"Field {field} must be optional OR vla!") - typestr = get_fully_defined_field_name(field, message_db) array_modifier = "" diff --git a/photon-serde/messages.yaml b/photon-serde/messages.yaml index 340e771807..1d7b8c155b 100644 --- a/photon-serde/messages.yaml +++ b/photon-serde/messages.yaml @@ -92,3 +92,7 @@ - name: multitagResult type: MultiTargetPNPResult optional: True + - name: rejectedTags + type: PhotonTrackedTarget + optional: True + vla: True diff --git a/photon-serde/templates/Message.java.jinja b/photon-serde/templates/Message.java.jinja index b1e27b68e9..6522bcdd13 100644 --- a/photon-serde/templates/Message.java.jinja +++ b/photon-serde/templates/Message.java.jinja @@ -63,8 +63,11 @@ public class {{ name }}Serde implements PacketSerde<{{name}}> { {%- for field in fields -%} {%- if field.type | is_shimmed %} {{ get_message_by_name(field.type).java_encode_shim }}(packet, value.{{ field.name }}); +{%- elif field.optional == True and field.vla == True %} + // {{ field.name }} is optional vla! + packet.encodeOptionalVla(value.{{ field.name }}); {%- elif field.optional == True %} - // {{ field.name }} is optional! it better not be a VLA too + // {{ field.name }} is optional! packet.encodeOptional(value.{{ field.name }}); {%- elif field.vla == True and field.type | is_intrinsic %} // {{ field.name }} is a intrinsic VLA! @@ -90,8 +93,11 @@ public class {{ name }}Serde implements PacketSerde<{{name}}> { {% for field in fields -%} {%- if field.type | is_shimmed %} ret.{{ field.name }} = {{ get_message_by_name(field.type).java_decode_shim }}(packet); +{%- elif field.optional == True and field.vla == True %} + // {{ field.name }} is optional vla! + ret.{{ field.name }} = packet.decodeOptionalVla({{ field.type }}.photonStruct); {%- elif field.optional == True %} - // {{ field.name }} is optional! it better not be a VLA too + // {{ field.name }} is optional! ret.{{ field.name }} = packet.decodeOptional({{ field.type }}.photonStruct); {%- elif field.vla == True and not field.type | is_intrinsic %} // {{ field.name }} is a custom VLA! diff --git a/photon-targeting/src/generated/main/java/org/photonvision/struct/PhotonPipelineResultSerde.java b/photon-targeting/src/generated/main/java/org/photonvision/struct/PhotonPipelineResultSerde.java index 5f9134fda8..4224c2a747 100644 --- a/photon-targeting/src/generated/main/java/org/photonvision/struct/PhotonPipelineResultSerde.java +++ b/photon-targeting/src/generated/main/java/org/photonvision/struct/PhotonPipelineResultSerde.java @@ -43,9 +43,9 @@ public class PhotonPipelineResultSerde implements PacketSerde { @Override - public final String getInterfaceUUID() { return "4b2ff16a964b5e2bf04be0c1454d91c4"; } + public final String getInterfaceUUID() { return "29e82c187da35e0337c86f4c14ee5ac7"; } @Override - public final String getSchema() { return "PhotonPipelineMetadata:ac0a45f686457856fb30af77699ea356 metadata;PhotonTrackedTarget:cc6dbb5c5c1e0fa808108019b20863f1 targets[?];optional MultiTargetPNPResult:541096947e9f3ca2d3f425ff7b04aa7b multitagResult;"; } + public final String getSchema() { return "PhotonPipelineMetadata:ac0a45f686457856fb30af77699ea356 metadata;PhotonTrackedTarget:cc6dbb5c5c1e0fa808108019b20863f1 targets[?];optional MultiTargetPNPResult:541096947e9f3ca2d3f425ff7b04aa7b multitagResult;optional PhotonTrackedTarget:cc6dbb5c5c1e0fa808108019b20863f1 rejectedTags[?];"; } @Override public final String getTypeName() { return "PhotonPipelineResult"; } @@ -63,8 +63,11 @@ public void pack(Packet packet, PhotonPipelineResult value) { // targets is a custom VLA! packet.encodeList(value.targets); - // multitagResult is optional! it better not be a VLA too + // multitagResult is optional! packet.encodeOptional(value.multitagResult); + + // rejectedTags is optional vla! + packet.encodeOptionalVla(value.rejectedTags); } @Override @@ -77,16 +80,19 @@ public PhotonPipelineResult unpack(Packet packet) { // targets is a custom VLA! ret.targets = packet.decodeList(PhotonTrackedTarget.photonStruct); - // multitagResult is optional! it better not be a VLA too + // multitagResult is optional! ret.multitagResult = packet.decodeOptional(MultiTargetPNPResult.photonStruct); + // rejectedTags is optional vla! + ret.rejectedTags = packet.decodeOptionalVla(PhotonTrackedTarget.photonStruct); + return ret; } @Override public PacketSerde[] getNestedPhotonMessages() { return new PacketSerde[] { - MultiTargetPNPResult.photonStruct,PhotonPipelineMetadata.photonStruct,PhotonTrackedTarget.photonStruct + PhotonPipelineMetadata.photonStruct,PhotonTrackedTarget.photonStruct,MultiTargetPNPResult.photonStruct }; } diff --git a/photon-targeting/src/generated/main/native/cpp/photon/serde/PhotonPipelineResultSerde.cpp b/photon-targeting/src/generated/main/native/cpp/photon/serde/PhotonPipelineResultSerde.cpp index eebb222826..b1e7d67dd5 100644 --- a/photon-targeting/src/generated/main/native/cpp/photon/serde/PhotonPipelineResultSerde.cpp +++ b/photon-targeting/src/generated/main/native/cpp/photon/serde/PhotonPipelineResultSerde.cpp @@ -34,6 +34,7 @@ void StructType::Pack(Packet& packet, const PhotonPipelineResult& value) { packet.Pack(value.metadata); packet.Pack>(value.targets); packet.Pack>(value.multitagResult); + packet.Pack>(value.rejectedTags); } PhotonPipelineResult StructType::Unpack(Packet& packet) { @@ -41,6 +42,7 @@ PhotonPipelineResult StructType::Unpack(Packet& packet) { .metadata = packet.Unpack(), .targets = packet.Unpack>(), .multitagResult = packet.Unpack>(), + .rejectedTags = packet.Unpack>(), }}; } diff --git a/photon-targeting/src/generated/main/native/include/photon/serde/PhotonPipelineResultSerde.h b/photon-targeting/src/generated/main/native/include/photon/serde/PhotonPipelineResultSerde.h index 836e347ca1..47786eec13 100644 --- a/photon-targeting/src/generated/main/native/include/photon/serde/PhotonPipelineResultSerde.h +++ b/photon-targeting/src/generated/main/native/include/photon/serde/PhotonPipelineResultSerde.h @@ -46,11 +46,11 @@ namespace photon { template <> struct WPILIB_DLLEXPORT SerdeType { static constexpr std::string_view GetSchemaHash() { - return "4b2ff16a964b5e2bf04be0c1454d91c4"; + return "29e82c187da35e0337c86f4c14ee5ac7"; } static constexpr std::string_view GetSchema() { - return "PhotonPipelineMetadata:ac0a45f686457856fb30af77699ea356 metadata;PhotonTrackedTarget:cc6dbb5c5c1e0fa808108019b20863f1 targets[?];optional MultiTargetPNPResult:541096947e9f3ca2d3f425ff7b04aa7b multitagResult;"; + return "PhotonPipelineMetadata:ac0a45f686457856fb30af77699ea356 metadata;PhotonTrackedTarget:cc6dbb5c5c1e0fa808108019b20863f1 targets[?];optional MultiTargetPNPResult:541096947e9f3ca2d3f425ff7b04aa7b multitagResult;optional PhotonTrackedTarget:cc6dbb5c5c1e0fa808108019b20863f1 rejectedTags[?];"; } static photon::PhotonPipelineResult Unpack(photon::Packet& packet); diff --git a/photon-targeting/src/generated/main/native/include/photon/struct/PhotonPipelineResultStruct.h b/photon-targeting/src/generated/main/native/include/photon/struct/PhotonPipelineResultStruct.h index 0d4fa4ac37..bcb1a184ff 100644 --- a/photon-targeting/src/generated/main/native/include/photon/struct/PhotonPipelineResultStruct.h +++ b/photon-targeting/src/generated/main/native/include/photon/struct/PhotonPipelineResultStruct.h @@ -41,6 +41,7 @@ struct PhotonPipelineResult_PhotonStruct { photon::PhotonPipelineMetadata metadata; std::vector targets; std::optional multitagResult; + std::optional rejectedTags; friend bool operator==(PhotonPipelineResult_PhotonStruct const&, PhotonPipelineResult_PhotonStruct const&) = default; }; diff --git a/photon-targeting/src/main/java/org/photonvision/common/dataflow/structures/Packet.java b/photon-targeting/src/main/java/org/photonvision/common/dataflow/structures/Packet.java index 62d5d2c2c0..3d8e90a79f 100644 --- a/photon-targeting/src/main/java/org/photonvision/common/dataflow/structures/Packet.java +++ b/photon-targeting/src/main/java/org/photonvision/common/dataflow/structures/Packet.java @@ -282,6 +282,13 @@ public > void encodeOptional(Optional d } } + public > void encodeOptionalVla(Optional> data) { + encode(data.isPresent()); + if (data.isPresent()) { + encodeList(data.get()); + } + } + /** * Returns a decoded byte from the packet. * @@ -427,6 +434,15 @@ public > Optional decodeOptional(Packet return Optional.empty(); } + public > Optional> decodeOptionalVla( + PacketSerde serde) { + var present = decodeBoolean(); + if (present) { + return Optional.of(decodeList(serde)); + } + return Optional.empty(); + } + public List decodeShortList() { byte length = decodeByte(); diff --git a/photon-targeting/src/main/java/org/photonvision/targeting/PhotonPipelineResult.java b/photon-targeting/src/main/java/org/photonvision/targeting/PhotonPipelineResult.java index 598e5eecd6..6d2cfc5ec6 100644 --- a/photon-targeting/src/main/java/org/photonvision/targeting/PhotonPipelineResult.java +++ b/photon-targeting/src/main/java/org/photonvision/targeting/PhotonPipelineResult.java @@ -40,9 +40,12 @@ public class PhotonPipelineResult // Multi-tag result public Optional multitagResult; + // Rejected tags + public Optional> rejectedTags; + /** Constructs an empty pipeline result. */ public PhotonPipelineResult() { - this(new PhotonPipelineMetadata(), List.of(), Optional.empty()); + this(new PhotonPipelineMetadata(), List.of(), Optional.empty(), Optional.empty()); } /** @@ -65,6 +68,7 @@ public PhotonPipelineResult( new PhotonPipelineMetadata( captureTimestampMicros, publishTimestampMicros, sequenceID, timeSinceLastPong), targets, + Optional.empty(), Optional.empty()); } @@ -85,21 +89,25 @@ public PhotonPipelineResult( long publishTimestamp, long timeSinceLastPong, List targets, - Optional result) { + Optional result, + Optional> rejectedTags) { this( new PhotonPipelineMetadata( captureTimestamp, publishTimestamp, sequenceID, timeSinceLastPong), targets, - result); + result, + rejectedTags); } public PhotonPipelineResult( PhotonPipelineMetadata metadata, List targets, - Optional result) { + Optional result, + Optional> rejectedTags) { this.metadata = metadata; this.targets.addAll(targets); this.multitagResult = result; + this.rejectedTags = rejectedTags; } /** diff --git a/photon-targeting/src/main/java/org/photonvision/targeting/proto/PhotonPipelineResultProto.java b/photon-targeting/src/main/java/org/photonvision/targeting/proto/PhotonPipelineResultProto.java index 97bf80e6cc..31653183b3 100644 --- a/photon-targeting/src/main/java/org/photonvision/targeting/proto/PhotonPipelineResultProto.java +++ b/photon-targeting/src/main/java/org/photonvision/targeting/proto/PhotonPipelineResultProto.java @@ -52,6 +52,9 @@ public PhotonPipelineResult unpack(ProtobufPhotonPipelineResult msg) { PhotonTrackedTarget.proto.unpack(msg.getTargets()), msg.hasMultiTargetResult() ? Optional.of(MultiTargetPNPResult.proto.unpack(msg.getMultiTargetResult())) + : Optional.empty(), + msg.hasRejectedTags() + ? Optional.of(PhotonTrackedTarget.proto.unpack(msg.getRejectedTags())) : Optional.empty()); } diff --git a/photon-targeting/src/main/java/org/photonvision/targeting/proto/PhotonTrackedTargetProto.java b/photon-targeting/src/main/java/org/photonvision/targeting/proto/PhotonTrackedTargetProto.java index 8bc68ad326..c652ecf87b 100644 --- a/photon-targeting/src/main/java/org/photonvision/targeting/proto/PhotonTrackedTargetProto.java +++ b/photon-targeting/src/main/java/org/photonvision/targeting/proto/PhotonTrackedTargetProto.java @@ -62,6 +62,14 @@ public PhotonTrackedTarget unpack(ProtobufPhotonTrackedTarget msg) { } public List unpack(RepeatedMessage msg) { + ArrayList targets = new ArrayList<>(msg.getTargets().length()); + for (ProtobufPhotonTrackedTarget target : msg.getTargets()) { + targets.add(unpack(target)); + } + return targets; + } + + public List unpack(ProtobufPhotonTrackedTargetList msg) { ArrayList targets = new ArrayList<>(msg.length()); for (ProtobufPhotonTrackedTarget target : msg) { targets.add(unpack(target)); diff --git a/photon-targeting/src/main/proto/photon.proto b/photon-targeting/src/main/proto/photon.proto index 0ff3991f9d..db8f2b5fad 100644 --- a/photon-targeting/src/main/proto/photon.proto +++ b/photon-targeting/src/main/proto/photon.proto @@ -57,16 +57,21 @@ message ProtobufPhotonTrackedTarget { float obj_detection_conf = 12; } +message ProtobufPhotonTrackedTargetList { + repeated ProtobufPhotonTrackedTarget targets = 1; +} + message ProtobufPhotonPipelineResult { double latency_ms = 1 [deprecated = true]; repeated ProtobufPhotonTrackedTarget targets = 2; optional ProtobufMultiTargetPNPResult multi_target_result = 3; + optional ProtobufPhotonTrackedTargetList rejectedTags = 4; - int64 sequence_id = 4; - int64 capture_timestamp_micros = 5; - int64 nt_publish_timestamp_micros = 6; - int64 time_since_last_pong_micros = 7; + int64 sequence_id = 5; + int64 capture_timestamp_micros = 6; + int64 nt_publish_timestamp_micros = 7; + int64 time_since_last_pong_micros = 8; } message ProtobufDeviceMetrics {