001/* 002 * MIT License 003 * 004 * Copyright (c) PhotonVision 005 * 006 * Permission is hereby granted, free of charge, to any person obtaining a copy 007 * of this software and associated documentation files (the "Software"), to deal 008 * in the Software without restriction, including without limitation the rights 009 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 010 * copies of the Software, and to permit persons to whom the Software is 011 * furnished to do so, subject to the following conditions: 012 * 013 * The above copyright notice and this permission notice shall be included in all 014 * copies or substantial portions of the Software. 015 * 016 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 017 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 018 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 019 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 020 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 021 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 022 * SOFTWARE. 023 */ 024 025package org.photonvision; 026 027import edu.wpi.first.hal.FRCNetComm.tResourceType; 028import edu.wpi.first.hal.HAL; 029import edu.wpi.first.math.MatBuilder; 030import edu.wpi.first.math.Matrix; 031import edu.wpi.first.math.Nat; 032import edu.wpi.first.math.numbers.*; 033import edu.wpi.first.networktables.BooleanPublisher; 034import edu.wpi.first.networktables.BooleanSubscriber; 035import edu.wpi.first.networktables.DoubleArraySubscriber; 036import edu.wpi.first.networktables.IntegerEntry; 037import edu.wpi.first.networktables.IntegerPublisher; 038import edu.wpi.first.networktables.IntegerSubscriber; 039import edu.wpi.first.networktables.MultiSubscriber; 040import edu.wpi.first.networktables.NetworkTable; 041import edu.wpi.first.networktables.NetworkTableInstance; 042import edu.wpi.first.networktables.PubSubOption; 043import edu.wpi.first.networktables.StringSubscriber; 044import edu.wpi.first.wpilibj.Alert; 045import edu.wpi.first.wpilibj.Alert.AlertType; 046import edu.wpi.first.wpilibj.DriverStation; 047import edu.wpi.first.wpilibj.Timer; 048import edu.wpi.first.wpilibj.util.WPILibVersion; 049import java.util.ArrayList; 050import java.util.Arrays; 051import java.util.List; 052import java.util.Optional; 053import java.util.stream.Collectors; 054import org.opencv.core.Core; 055import org.photonvision.common.hardware.VisionLEDMode; 056import org.photonvision.common.networktables.PacketSubscriber; 057import org.photonvision.targeting.PhotonPipelineResult; 058import org.photonvision.timesync.TimeSyncSingleton; 059 060/** Represents a camera that is connected to PhotonVision. */ 061public class PhotonCamera implements AutoCloseable { 062 private static int InstanceCount = 0; 063 public static final String kTableName = "photonvision"; 064 private static final String PHOTON_ALERT_GROUP = "PhotonAlerts"; 065 066 private final NetworkTable cameraTable; 067 PacketSubscriber<PhotonPipelineResult> resultSubscriber; 068 BooleanPublisher driverModePublisher; 069 BooleanSubscriber driverModeSubscriber; 070 StringSubscriber versionEntry; 071 IntegerEntry inputSaveImgEntry, outputSaveImgEntry; 072 IntegerPublisher pipelineIndexRequest, ledModeRequest; 073 IntegerSubscriber pipelineIndexState, ledModeState; 074 IntegerSubscriber heartbeatSubscriber; 075 DoubleArraySubscriber cameraIntrinsicsSubscriber; 076 DoubleArraySubscriber cameraDistortionSubscriber; 077 MultiSubscriber topicNameSubscriber; 078 NetworkTable rootPhotonTable; 079 080 @Override 081 public void close() { 082 resultSubscriber.close(); 083 driverModePublisher.close(); 084 driverModeSubscriber.close(); 085 versionEntry.close(); 086 inputSaveImgEntry.close(); 087 outputSaveImgEntry.close(); 088 pipelineIndexRequest.close(); 089 pipelineIndexState.close(); 090 ledModeRequest.close(); 091 ledModeState.close(); 092 pipelineIndexRequest.close(); 093 cameraIntrinsicsSubscriber.close(); 094 cameraDistortionSubscriber.close(); 095 topicNameSubscriber.close(); 096 } 097 098 private final String path; 099 private final String name; 100 101 private static boolean VERSION_CHECK_ENABLED = true; 102 private static long VERSION_CHECK_INTERVAL = 5; 103 double lastVersionCheckTime = 0; 104 105 private long prevHeartbeatValue = -1; 106 private double prevHeartbeatChangeTime = 0; 107 private static final double HEARTBEAT_DEBOUNCE_SEC = 0.5; 108 109 double prevTimeSyncWarnTime = 0; 110 private static final double WARN_DEBOUNCE_SEC = 5; 111 112 private final Alert disconnectAlert; 113 private final Alert timesyncAlert; 114 115 public static void setVersionCheckEnabled(boolean enabled) { 116 VERSION_CHECK_ENABLED = enabled; 117 } 118 119 /** 120 * Constructs a PhotonCamera from a root table. 121 * 122 * @param instance The NetworkTableInstance to pull data from. This can be a custom instance in 123 * simulation, but should *usually* be the default NTInstance from 124 * NetworkTableInstance::getDefault 125 * @param cameraName The name of the camera, as seen in the UI. 126 */ 127 public PhotonCamera(NetworkTableInstance instance, String cameraName) { 128 name = cameraName; 129 disconnectAlert = 130 new Alert( 131 PHOTON_ALERT_GROUP, "PhotonCamera '" + name + "' is disconnected.", AlertType.kWarning); 132 timesyncAlert = new Alert(PHOTON_ALERT_GROUP, "", AlertType.kWarning); 133 rootPhotonTable = instance.getTable(kTableName); 134 this.cameraTable = rootPhotonTable.getSubTable(cameraName); 135 path = cameraTable.getPath(); 136 var rawBytesEntry = 137 cameraTable 138 .getRawTopic("rawBytes") 139 .subscribe( 140 PhotonPipelineResult.photonStruct.getTypeString(), 141 new byte[] {}, 142 PubSubOption.periodic(0.01), 143 PubSubOption.sendAll(true), 144 PubSubOption.pollStorage(20)); 145 resultSubscriber = new PacketSubscriber<>(rawBytesEntry, PhotonPipelineResult.photonStruct); 146 driverModePublisher = cameraTable.getBooleanTopic("driverModeRequest").publish(); 147 driverModeSubscriber = cameraTable.getBooleanTopic("driverMode").subscribe(false); 148 inputSaveImgEntry = cameraTable.getIntegerTopic("inputSaveImgCmd").getEntry(0); 149 outputSaveImgEntry = cameraTable.getIntegerTopic("outputSaveImgCmd").getEntry(0); 150 pipelineIndexRequest = cameraTable.getIntegerTopic("pipelineIndexRequest").publish(); 151 pipelineIndexState = cameraTable.getIntegerTopic("pipelineIndexState").subscribe(0); 152 heartbeatSubscriber = cameraTable.getIntegerTopic("heartbeat").subscribe(-1); 153 cameraIntrinsicsSubscriber = 154 cameraTable.getDoubleArrayTopic("cameraIntrinsics").subscribe(null); 155 cameraDistortionSubscriber = 156 cameraTable.getDoubleArrayTopic("cameraDistortion").subscribe(null); 157 158 ledModeRequest = rootPhotonTable.getIntegerTopic("ledModeRequest").publish(); 159 ledModeState = rootPhotonTable.getIntegerTopic("ledModeState").subscribe(-1); 160 versionEntry = rootPhotonTable.getStringTopic("version").subscribe(""); 161 162 // Existing is enough to make this multisubscriber do its thing 163 topicNameSubscriber = 164 new MultiSubscriber( 165 instance, new String[] {"/photonvision/"}, PubSubOption.topicsOnly(true)); 166 167 HAL.report(tResourceType.kResourceType_PhotonCamera, InstanceCount); 168 InstanceCount++; 169 170 // HACK - start a TimeSyncServer, if we haven't yet. 171 TimeSyncSingleton.load(); 172 173 // HACK - check if things are compatible 174 verifyDependencies(); 175 } 176 177 public static void verifyDependencies() { 178 if (!WPILibVersion.Version.equals(PhotonVersion.wpilibTargetVersion)) { 179 String bfw = 180 "\n\n\n\n\n" 181 + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n" 182 + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" 183 + ">>> \n" 184 + ">>> You are running an incompatible version \n" 185 + ">>> of PhotonVision ! \n" 186 + ">>> \n" 187 + ">>> PhotonLib " 188 + PhotonVersion.versionString 189 + " is built for WPILib " 190 + PhotonVersion.wpilibTargetVersion 191 + "\n" 192 + ">>> but you are using WPILib " 193 + WPILibVersion.Version 194 + ">>> \n" 195 + ">>> This is neither tested nor supported. \n" 196 + ">>> You MUST update PhotonVision, \n" 197 + ">>> PhotonLib, or both. \n" 198 + ">>> Verify the output of `./gradlew dependencies` \n" 199 + ">>> \n" 200 + ">>> Your code will now crash. \n" 201 + ">>> We hope your day gets better. \n" 202 + ">>> \n" 203 + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" 204 + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n"; 205 206 DriverStation.reportWarning(bfw, false); 207 DriverStation.reportError(bfw, false); 208 throw new UnsupportedOperationException(bfw); 209 } 210 if (!Core.VERSION.equals(PhotonVersion.opencvTargetVersion)) { 211 String bfw = 212 "\n\n\n\n\n" 213 + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n" 214 + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" 215 + ">>> \n" 216 + ">>> You are running an incompatible version \n" 217 + ">>> of PhotonVision ! \n" 218 + ">>> \n" 219 + ">>> PhotonLib " 220 + PhotonVersion.versionString 221 + " is built for OpenCV " 222 + PhotonVersion.opencvTargetVersion 223 + "\n" 224 + ">>> but you are using OpenCV " 225 + Core.VERSION 226 + ">>> \n" 227 + ">>> This is neither tested nor supported. \n" 228 + ">>> You MUST update PhotonVision, \n" 229 + ">>> PhotonLib, or both. \n" 230 + ">>> Verify the output of `./gradlew dependencies` \n" 231 + ">>> \n" 232 + ">>> Your code will now crash. \n" 233 + ">>> We hope your day gets better. \n" 234 + ">>> \n" 235 + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" 236 + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n"; 237 238 DriverStation.reportWarning(bfw, false); 239 DriverStation.reportError(bfw, false); 240 throw new UnsupportedOperationException(bfw); 241 } 242 } 243 244 /** 245 * Constructs a PhotonCamera from the name of the camera. 246 * 247 * @param cameraName The nickname of the camera (found in the PhotonVision UI). 248 */ 249 public PhotonCamera(String cameraName) { 250 this(NetworkTableInstance.getDefault(), cameraName); 251 } 252 253 /** 254 * The list of pipeline results sent by PhotonVision since the last call to getAllUnreadResults(). 255 * Calling this function clears the internal FIFO queue, and multiple calls to 256 * getAllUnreadResults() will return different (potentially empty) result arrays. Be careful to 257 * call this exactly ONCE per loop of your robot code! FIFO depth is limited to 20 changes, so 258 * make sure to call this frequently enough to avoid old results being discarded, too! 259 */ 260 public List<PhotonPipelineResult> getAllUnreadResults() { 261 verifyVersion(); 262 updateDisconnectAlert(); 263 264 List<PhotonPipelineResult> ret = new ArrayList<>(); 265 266 // Grab the latest results. We don't care about the timestamps from NT - the metadata header has 267 // this, latency compensated by the Time Sync Client 268 var changes = resultSubscriber.getAllChanges(); 269 for (var c : changes) { 270 var result = c.value; 271 checkTimeSyncOrWarn(result); 272 ret.add(result); 273 } 274 275 return ret; 276 } 277 278 /** 279 * Returns the latest pipeline result. This is simply the most recent result Received via NT. 280 * Calling this multiple times will always return the most recent result. 281 * 282 * <p>Replaced by {@link #getAllUnreadResults()} over getLatestResult, as this function can miss 283 * results, or provide duplicate ones! 284 */ 285 @Deprecated(since = "2024", forRemoval = true) 286 public PhotonPipelineResult getLatestResult() { 287 verifyVersion(); 288 updateDisconnectAlert(); 289 290 // Grab the latest result. We don't care about the timestamp from NT - the metadata header has 291 // this, latency compensated by the Time Sync Client 292 var ret = resultSubscriber.get(); 293 294 if (ret.timestamp == 0) return new PhotonPipelineResult(); 295 296 var result = ret.value; 297 298 checkTimeSyncOrWarn(result); 299 300 return result; 301 } 302 303 private void updateDisconnectAlert() { 304 disconnectAlert.set(!isConnected()); 305 } 306 307 private void checkTimeSyncOrWarn(PhotonPipelineResult result) { 308 if (result.metadata.timeSinceLastPong > 5L * 1000000L) { 309 String warningText = 310 "PhotonVision coprocessor at path " 311 + path 312 + " is not connected to the TimeSyncServer? It's been " 313 + String.format("%.2f", result.metadata.timeSinceLastPong / 1e6) 314 + "s since the coprocessor last heard a pong."; 315 316 timesyncAlert.setText(warningText); 317 timesyncAlert.set(true); 318 319 if (Timer.getFPGATimestamp() > (prevTimeSyncWarnTime + WARN_DEBOUNCE_SEC)) { 320 prevTimeSyncWarnTime = Timer.getFPGATimestamp(); 321 322 DriverStation.reportWarning( 323 warningText 324 + "\n\nCheck /photonvision/.timesync/{COPROCESSOR_HOSTNAME} for more information.", 325 false); 326 } 327 } else { 328 // Got a valid packet, reset the last time 329 prevTimeSyncWarnTime = 0; 330 timesyncAlert.set(false); 331 } 332 } 333 334 /** 335 * Returns whether the camera is in driver mode. 336 * 337 * @return Whether the camera is in driver mode. 338 */ 339 public boolean getDriverMode() { 340 return driverModeSubscriber.get(); 341 } 342 343 /** 344 * Toggles driver mode. 345 * 346 * @param driverMode Whether to set driver mode. 347 */ 348 public void setDriverMode(boolean driverMode) { 349 driverModePublisher.set(driverMode); 350 } 351 352 /** 353 * Request the camera to save a new image file from the input camera stream with overlays. Images 354 * take up space in the filesystem of the PhotonCamera. Calling it frequently will fill up disk 355 * space and eventually cause the system to stop working. Clear out images in 356 * /opt/photonvision/photonvision_config/imgSaves frequently to prevent issues. 357 */ 358 public void takeInputSnapshot() { 359 inputSaveImgEntry.set(inputSaveImgEntry.get() + 1); 360 } 361 362 /** 363 * Request the camera to save a new image file from the output stream with overlays. Images take 364 * up space in the filesystem of the PhotonCamera. Calling it frequently will fill up disk space 365 * and eventually cause the system to stop working. Clear out images in 366 * /opt/photonvision/photonvision_config/imgSaves frequently to prevent issues. 367 */ 368 public void takeOutputSnapshot() { 369 outputSaveImgEntry.set(outputSaveImgEntry.get() + 1); 370 } 371 372 /** 373 * Returns the active pipeline index. 374 * 375 * @return The active pipeline index. 376 */ 377 public int getPipelineIndex() { 378 return (int) pipelineIndexState.get(0); 379 } 380 381 /** 382 * Allows the user to select the active pipeline index. 383 * 384 * @param index The active pipeline index. 385 */ 386 public void setPipelineIndex(int index) { 387 pipelineIndexRequest.set(index); 388 } 389 390 /** 391 * Returns the current LED mode. 392 * 393 * @return The current LED mode. 394 */ 395 public VisionLEDMode getLEDMode() { 396 int value = (int) ledModeState.get(-1); 397 return switch (value) { 398 case 0 -> VisionLEDMode.kOff; 399 case 1 -> VisionLEDMode.kOn; 400 case 2 -> VisionLEDMode.kBlink; 401 default -> VisionLEDMode.kDefault; 402 }; 403 } 404 405 /** 406 * Sets the LED mode. 407 * 408 * @param led The mode to set to. 409 */ 410 public void setLED(VisionLEDMode led) { 411 ledModeRequest.set(led.value); 412 } 413 414 /** 415 * Returns the name of the camera. This will return the same value that was given to the 416 * constructor as cameraName. 417 * 418 * @return The name of the camera. 419 */ 420 public String getName() { 421 return name; 422 } 423 424 /** 425 * Returns whether the camera is connected and actively returning new data. Connection status is 426 * debounced. 427 * 428 * @return True if the camera is actively sending frame data, false otherwise. 429 */ 430 public boolean isConnected() { 431 var curHeartbeat = heartbeatSubscriber.get(); 432 var now = Timer.getFPGATimestamp(); 433 434 if (curHeartbeat < 0) { 435 // we have never heard from the camera 436 return false; 437 } 438 439 if (curHeartbeat != prevHeartbeatValue) { 440 // New heartbeat value from the coprocessor 441 prevHeartbeatChangeTime = now; 442 prevHeartbeatValue = curHeartbeat; 443 } 444 445 return (now - prevHeartbeatChangeTime) < HEARTBEAT_DEBOUNCE_SEC; 446 } 447 448 public Optional<Matrix<N3, N3>> getCameraMatrix() { 449 var cameraMatrix = cameraIntrinsicsSubscriber.get(); 450 if (cameraMatrix != null && cameraMatrix.length == 9) { 451 return Optional.of(MatBuilder.fill(Nat.N3(), Nat.N3(), cameraMatrix)); 452 } else return Optional.empty(); 453 } 454 455 /** 456 * The camera calibration's distortion coefficients, in OPENCV8 form. Higher-order terms are set 457 * to 0 458 */ 459 public Optional<Matrix<N8, N1>> getDistCoeffs() { 460 var distCoeffs = cameraDistortionSubscriber.get(); 461 if (distCoeffs != null && distCoeffs.length <= 8) { 462 // Copy into array of length 8, and explicitly null higher order terms out 463 double[] data = new double[8]; 464 Arrays.fill(data, 0); 465 System.arraycopy(distCoeffs, 0, data, 0, distCoeffs.length); 466 467 return Optional.of(MatBuilder.fill(Nat.N8(), Nat.N1(), data)); 468 } else return Optional.empty(); 469 } 470 471 /** 472 * Gets the NetworkTable representing this camera's subtable. You probably don't ever need to call 473 * this. 474 */ 475 public final NetworkTable getCameraTable() { 476 return cameraTable; 477 } 478 479 void verifyVersion() { 480 if (!VERSION_CHECK_ENABLED) return; 481 482 if ((Timer.getFPGATimestamp() - lastVersionCheckTime) < VERSION_CHECK_INTERVAL) return; 483 lastVersionCheckTime = Timer.getFPGATimestamp(); 484 485 // Heartbeat entry is assumed to always be present. If it's not present, we 486 // assume that a camera with that name was never connected in the first place. 487 if (!heartbeatSubscriber.exists()) { 488 var cameraNames = getTablesThatLookLikePhotonCameras(); 489 if (cameraNames.isEmpty()) { 490 DriverStation.reportError( 491 "Could not find **any** PhotonVision coprocessors on NetworkTables. Double check that PhotonVision is running, and that your camera is connected!", 492 false); 493 } else { 494 DriverStation.reportError( 495 "PhotonVision coprocessor at path " 496 + path 497 + " not found on NetworkTables. Double check that your camera names match!", 498 true); 499 500 var cameraNameStr = new StringBuilder(); 501 for (var c : cameraNames) { 502 cameraNameStr.append(" ==> "); 503 cameraNameStr.append(c); 504 cameraNameStr.append("\n"); 505 } 506 507 DriverStation.reportError( 508 "Found the following PhotonVision cameras on NetworkTables:\n" 509 + cameraNameStr.toString(), 510 false); 511 } 512 } 513 // Check for connection status. Warn if disconnected. 514 else if (!isConnected()) { 515 DriverStation.reportWarning( 516 "PhotonVision coprocessor at path " + path + " is not sending new data.", false); 517 } 518 519 String versionString = versionEntry.get(""); 520 521 // Check mdef UUID 522 String local_uuid = PhotonPipelineResult.photonStruct.getInterfaceUUID(); 523 String remote_uuid = resultSubscriber.getInterfaceUUID(); 524 525 if (remote_uuid == null || remote_uuid.isEmpty()) { 526 // not connected yet? 527 DriverStation.reportWarning( 528 "PhotonVision coprocessor at path " 529 + path 530 + " has not reported a message interface UUID - is your coprocessor's camera started?", 531 false); 532 } else if (!local_uuid.equals(remote_uuid)) { 533 // Error on a verified version mismatch 534 // But stay silent otherwise 535 536 String bfw = 537 "\n\n\n\n\n" 538 + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n" 539 + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" 540 + ">>> \n" 541 + ">>> You are running an incompatible version \n" 542 + ">>> of PhotonVision on your coprocessor! \n" 543 + ">>> \n" 544 + ">>> This is neither tested nor supported. \n" 545 + ">>> You MUST update PhotonVision, \n" 546 + ">>> PhotonLib, or both. \n" 547 + ">>> \n" 548 + ">>> Your code will now crash. \n" 549 + ">>> We hope your day gets better. \n" 550 + ">>> \n" 551 + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" 552 + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n"; 553 554 DriverStation.reportWarning(bfw, false); 555 var versionMismatchMessage = 556 "Photon version " 557 + PhotonVersion.versionString 558 + " (message definition version " 559 + local_uuid 560 + ")" 561 + " does not match coprocessor version " 562 + versionString 563 + " (message definition version " 564 + remote_uuid 565 + ")" 566 + "!"; 567 DriverStation.reportError(versionMismatchMessage, false); 568 throw new UnsupportedOperationException(versionMismatchMessage); 569 } 570 } 571 572 private List<String> getTablesThatLookLikePhotonCameras() { 573 return rootPhotonTable.getSubTables().stream() 574 .filter( 575 it -> { 576 return rootPhotonTable.getSubTable(it).getEntry("rawBytes").exists(); 577 }) 578 .collect(Collectors.toList()); 579 } 580}