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