001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.cameraserver; 006 007import edu.wpi.first.cscore.AxisCamera; 008import edu.wpi.first.cscore.CameraServerJNI; 009import edu.wpi.first.cscore.CvSink; 010import edu.wpi.first.cscore.CvSource; 011import edu.wpi.first.cscore.MjpegServer; 012import edu.wpi.first.cscore.UsbCamera; 013import edu.wpi.first.cscore.VideoEvent; 014import edu.wpi.first.cscore.VideoException; 015import edu.wpi.first.cscore.VideoListener; 016import edu.wpi.first.cscore.VideoMode; 017import edu.wpi.first.cscore.VideoSink; 018import edu.wpi.first.cscore.VideoSource; 019import edu.wpi.first.networktables.BooleanEntry; 020import edu.wpi.first.networktables.BooleanPublisher; 021import edu.wpi.first.networktables.IntegerEntry; 022import edu.wpi.first.networktables.IntegerPublisher; 023import edu.wpi.first.networktables.NetworkTable; 024import edu.wpi.first.networktables.NetworkTableInstance; 025import edu.wpi.first.networktables.StringArrayPublisher; 026import edu.wpi.first.networktables.StringArrayTopic; 027import edu.wpi.first.networktables.StringEntry; 028import edu.wpi.first.networktables.StringPublisher; 029import edu.wpi.first.util.PixelFormat; 030import java.lang.ref.Reference; 031import java.util.ArrayList; 032import java.util.Arrays; 033import java.util.HashMap; 034import java.util.Map; 035import java.util.Objects; 036import java.util.concurrent.atomic.AtomicInteger; 037 038/** 039 * Singleton class for creating and keeping camera servers. Also publishes camera information to 040 * NetworkTables. 041 */ 042public final class CameraServer { 043 /** CameraServer base port. */ 044 public static final int kBasePort = 1181; 045 046 private static final String kPublishName = "/CameraPublisher"; 047 048 private static final class PropertyPublisher implements AutoCloseable { 049 @SuppressWarnings({"PMD.MissingBreakInSwitch", "PMD.ImplicitSwitchFallThrough", "fallthrough"}) 050 PropertyPublisher(NetworkTable table, VideoEvent event) { 051 String name; 052 String infoName; 053 if (event.name.startsWith("raw_")) { 054 name = "RawProperty/" + event.name; 055 infoName = "RawPropertyInfo/" + event.name; 056 } else { 057 name = "Property/" + event.name; 058 infoName = "PropertyInfo/" + event.name; 059 } 060 061 try { 062 switch (event.propertyKind) { 063 case kBoolean: 064 m_booleanValueEntry = table.getBooleanTopic(name).getEntry(false); 065 m_booleanValueEntry.setDefault(event.value != 0); 066 break; 067 case kEnum: 068 m_choicesTopic = table.getStringArrayTopic(infoName + "/choices"); 069 // fall through 070 case kInteger: 071 m_integerValueEntry = table.getIntegerTopic(name).getEntry(0); 072 m_minPublisher = table.getIntegerTopic(infoName + "/min").publish(); 073 m_maxPublisher = table.getIntegerTopic(infoName + "/max").publish(); 074 m_stepPublisher = table.getIntegerTopic(infoName + "/step").publish(); 075 m_defaultPublisher = table.getIntegerTopic(infoName + "/default").publish(); 076 077 m_integerValueEntry.setDefault(event.value); 078 m_minPublisher.set(CameraServerJNI.getPropertyMin(event.propertyHandle)); 079 m_maxPublisher.set(CameraServerJNI.getPropertyMax(event.propertyHandle)); 080 m_stepPublisher.set(CameraServerJNI.getPropertyStep(event.propertyHandle)); 081 m_defaultPublisher.set(CameraServerJNI.getPropertyDefault(event.propertyHandle)); 082 break; 083 case kString: 084 m_stringValueEntry = table.getStringTopic(name).getEntry(""); 085 m_stringValueEntry.setDefault(event.valueStr); 086 break; 087 default: 088 break; 089 } 090 } catch (VideoException ignored) { 091 // ignore 092 } 093 } 094 095 void update(VideoEvent event) { 096 switch (event.propertyKind) { 097 case kBoolean: 098 if (m_booleanValueEntry != null) { 099 m_booleanValueEntry.set(event.value != 0); 100 } 101 break; 102 case kInteger: 103 case kEnum: 104 if (m_integerValueEntry != null) { 105 m_integerValueEntry.set(event.value); 106 } 107 break; 108 case kString: 109 if (m_stringValueEntry != null) { 110 m_stringValueEntry.set(event.valueStr); 111 } 112 break; 113 default: 114 break; 115 } 116 } 117 118 @Override 119 public void close() { 120 if (m_booleanValueEntry != null) { 121 m_booleanValueEntry.close(); 122 } 123 if (m_integerValueEntry != null) { 124 m_integerValueEntry.close(); 125 } 126 if (m_stringValueEntry != null) { 127 m_stringValueEntry.close(); 128 } 129 if (m_minPublisher != null) { 130 m_minPublisher.close(); 131 } 132 if (m_maxPublisher != null) { 133 m_maxPublisher.close(); 134 } 135 if (m_stepPublisher != null) { 136 m_stepPublisher.close(); 137 } 138 if (m_defaultPublisher != null) { 139 m_defaultPublisher.close(); 140 } 141 if (m_choicesPublisher != null) { 142 m_choicesPublisher.close(); 143 } 144 Reference.reachabilityFence(m_videoListener); 145 } 146 147 BooleanEntry m_booleanValueEntry; 148 IntegerEntry m_integerValueEntry; 149 StringEntry m_stringValueEntry; 150 IntegerPublisher m_minPublisher; 151 IntegerPublisher m_maxPublisher; 152 IntegerPublisher m_stepPublisher; 153 IntegerPublisher m_defaultPublisher; 154 StringArrayTopic m_choicesTopic; 155 StringArrayPublisher m_choicesPublisher; 156 } 157 158 private static final class SourcePublisher implements AutoCloseable { 159 SourcePublisher(NetworkTable table, int sourceHandle) { 160 this.m_table = table; 161 m_sourcePublisher = table.getStringTopic("source").publish(); 162 m_descriptionPublisher = table.getStringTopic("description").publish(); 163 m_connectedPublisher = table.getBooleanTopic("connected").publish(); 164 m_streamsPublisher = table.getStringArrayTopic("streams").publish(); 165 m_modeEntry = table.getStringTopic("mode").getEntry(""); 166 m_modesPublisher = table.getStringArrayTopic("modes").publish(); 167 168 m_sourcePublisher.set(makeSourceValue(sourceHandle)); 169 m_descriptionPublisher.set(CameraServerJNI.getSourceDescription(sourceHandle)); 170 m_connectedPublisher.set(CameraServerJNI.isSourceConnected(sourceHandle)); 171 m_streamsPublisher.set(getSourceStreamValues(sourceHandle)); 172 173 try { 174 VideoMode mode = CameraServerJNI.getSourceVideoMode(sourceHandle); 175 m_modeEntry.setDefault(videoModeToString(mode)); 176 m_modesPublisher.set(getSourceModeValues(sourceHandle)); 177 } catch (VideoException ignored) { 178 // Do nothing. Let the other event handlers update this if there is an error. 179 } 180 } 181 182 @Override 183 public void close() throws Exception { 184 m_sourcePublisher.close(); 185 m_descriptionPublisher.close(); 186 m_connectedPublisher.close(); 187 m_streamsPublisher.close(); 188 m_modeEntry.close(); 189 m_modesPublisher.close(); 190 for (PropertyPublisher pp : m_properties.values()) { 191 pp.close(); 192 } 193 } 194 195 final NetworkTable m_table; 196 final StringPublisher m_sourcePublisher; 197 final StringPublisher m_descriptionPublisher; 198 final BooleanPublisher m_connectedPublisher; 199 final StringArrayPublisher m_streamsPublisher; 200 final StringEntry m_modeEntry; 201 final StringArrayPublisher m_modesPublisher; 202 final Map<Integer, PropertyPublisher> m_properties = new HashMap<>(); 203 } 204 205 private static final AtomicInteger m_defaultUsbDevice = new AtomicInteger(); 206 private static String m_primarySourceName; 207 private static final Map<String, VideoSource> m_sources = new HashMap<>(); 208 private static final Map<String, VideoSink> m_sinks = new HashMap<>(); 209 private static final Map<Integer, SourcePublisher> m_publishers = 210 new HashMap<>(); // indexed by source handle 211 // source handle indexed by sink handle 212 private static final Map<Integer, Integer> m_fixedSources = new HashMap<>(); 213 private static final NetworkTable m_publishTable = 214 NetworkTableInstance.getDefault().getTable(kPublishName); 215 216 // We publish sources to NetworkTables using the following structure: 217 // "/CameraPublisher/{Source.Name}/" - root 218 // - "source" (string): Descriptive, prefixed with type (e.g. "usb:0") 219 // - "streams" (string array): URLs that can be used to stream data 220 // - "description" (string): Description of the source 221 // - "connected" (boolean): Whether source is connected 222 // - "mode" (string): Current video mode 223 // - "modes" (string array): Available video modes 224 // - "Property/{Property}" - Property values 225 // - "PropertyInfo/{Property}" - Property supporting information 226 227 // Listener for video events 228 @SuppressWarnings("PMD.AvoidCatchingGenericException") 229 private static final VideoListener m_videoListener = 230 new VideoListener( 231 event -> { 232 synchronized (CameraServer.class) { 233 switch (event.kind) { 234 case kSourceCreated: 235 { 236 // Create subtable for the camera 237 NetworkTable table = m_publishTable.getSubTable(event.name); 238 m_publishers.put( 239 event.sourceHandle, new SourcePublisher(table, event.sourceHandle)); 240 break; 241 } 242 case kSourceDestroyed: 243 { 244 SourcePublisher publisher = m_publishers.remove(event.sourceHandle); 245 if (publisher != null) { 246 try { 247 publisher.close(); 248 } catch (Exception e) { 249 // ignore (nothing we can do about it) 250 } 251 } 252 break; 253 } 254 case kSourceConnected: 255 { 256 SourcePublisher publisher = m_publishers.get(event.sourceHandle); 257 if (publisher != null) { 258 // update the description too (as it may have changed) 259 publisher.m_descriptionPublisher.set( 260 CameraServerJNI.getSourceDescription(event.sourceHandle)); 261 publisher.m_connectedPublisher.set(true); 262 } 263 break; 264 } 265 case kSourceDisconnected: 266 { 267 SourcePublisher publisher = m_publishers.get(event.sourceHandle); 268 if (publisher != null) { 269 publisher.m_connectedPublisher.set(false); 270 } 271 break; 272 } 273 case kSourceVideoModesUpdated: 274 { 275 SourcePublisher publisher = m_publishers.get(event.sourceHandle); 276 if (publisher != null) { 277 publisher.m_modesPublisher.set(getSourceModeValues(event.sourceHandle)); 278 } 279 break; 280 } 281 case kSourceVideoModeChanged: 282 { 283 SourcePublisher publisher = m_publishers.get(event.sourceHandle); 284 if (publisher != null) { 285 publisher.m_modeEntry.set(videoModeToString(event.mode)); 286 } 287 break; 288 } 289 case kSourcePropertyCreated: 290 { 291 SourcePublisher publisher = m_publishers.get(event.sourceHandle); 292 if (publisher != null) { 293 publisher.m_properties.put( 294 event.propertyHandle, new PropertyPublisher(publisher.m_table, event)); 295 } 296 break; 297 } 298 case kSourcePropertyValueUpdated: 299 { 300 SourcePublisher publisher = m_publishers.get(event.sourceHandle); 301 if (publisher != null) { 302 PropertyPublisher pp = publisher.m_properties.get(event.propertyHandle); 303 if (pp != null) { 304 pp.update(event); 305 } 306 } 307 break; 308 } 309 case kSourcePropertyChoicesUpdated: 310 { 311 SourcePublisher publisher = m_publishers.get(event.sourceHandle); 312 if (publisher != null) { 313 PropertyPublisher pp = publisher.m_properties.get(event.propertyHandle); 314 if (pp != null && pp.m_choicesTopic != null) { 315 try { 316 String[] choices = 317 CameraServerJNI.getEnumPropertyChoices(event.propertyHandle); 318 if (pp.m_choicesPublisher == null) { 319 pp.m_choicesPublisher = pp.m_choicesTopic.publish(); 320 } 321 pp.m_choicesPublisher.set(choices); 322 } catch (VideoException ignored) { 323 // ignore (just don't publish choices if we can't get them) 324 } 325 } 326 } 327 break; 328 } 329 case kSinkSourceChanged: 330 case kSinkCreated: 331 case kSinkDestroyed: 332 case kNetworkInterfacesChanged: 333 { 334 m_addresses = CameraServerJNI.getNetworkInterfaces(); 335 updateStreamValues(); 336 break; 337 } 338 default: 339 break; 340 } 341 } 342 }, 343 0x4fff, 344 true); 345 346 private static int m_nextPort = kBasePort; 347 private static String[] m_addresses = new String[0]; 348 349 /** 350 * Return URI of source with the given index. 351 * 352 * @param source Source index. 353 */ 354 private static String makeSourceValue(int source) { 355 switch (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))) { 356 case kUsb: 357 return "usb:" + CameraServerJNI.getUsbCameraPath(source); 358 case kHttp: 359 { 360 String[] urls = CameraServerJNI.getHttpCameraUrls(source); 361 if (urls.length > 0) { 362 return "ip:" + urls[0]; 363 } else { 364 return "ip:"; 365 } 366 } 367 case kCv: 368 return "cv:"; 369 default: 370 return "unknown:"; 371 } 372 } 373 374 /** 375 * Return URI of stream with the given address and port. 376 * 377 * @param address Stream IP address. 378 * @param port Stream remote port. 379 */ 380 private static String makeStreamValue(String address, int port) { 381 return "mjpg:http://" + address + ":" + port + "/?action=stream"; 382 } 383 384 /** 385 * Return URI of sink stream with the given index. 386 * 387 * @param sink Sink index. 388 */ 389 private static synchronized String[] getSinkStreamValues(int sink) { 390 // Ignore all but MjpegServer 391 if (VideoSink.getKindFromInt(CameraServerJNI.getSinkKind(sink)) != VideoSink.Kind.kMjpeg) { 392 return new String[0]; 393 } 394 395 // Get port 396 int port = CameraServerJNI.getMjpegServerPort(sink); 397 398 // Generate values 399 ArrayList<String> values = new ArrayList<>(m_addresses.length + 1); 400 String listenAddress = CameraServerJNI.getMjpegServerListenAddress(sink); 401 if (!listenAddress.isEmpty()) { 402 // If a listen address is specified, only use that 403 values.add(makeStreamValue(listenAddress, port)); 404 } else { 405 // Otherwise generate for hostname and all interface addresses 406 values.add(makeStreamValue(CameraServerJNI.getHostname() + ".local", port)); 407 for (String addr : m_addresses) { 408 if ("127.0.0.1".equals(addr)) { 409 continue; // ignore localhost 410 } 411 values.add(makeStreamValue(addr, port)); 412 } 413 } 414 415 return values.toArray(new String[0]); 416 } 417 418 /** 419 * Return list of stream source URIs for the given source index. 420 * 421 * @param source Source index. 422 */ 423 private static synchronized String[] getSourceStreamValues(int source) { 424 // Ignore all but HttpCamera 425 if (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source)) 426 != VideoSource.Kind.kHttp) { 427 return new String[0]; 428 } 429 430 // Generate values 431 String[] values = CameraServerJNI.getHttpCameraUrls(source); 432 for (int j = 0; j < values.length; j++) { 433 values[j] = "mjpg:" + values[j]; 434 } 435 436 if (CameraServerSharedStore.getCameraServerShared().isRoboRIO()) { 437 // Look to see if we have a passthrough server for this source 438 // Only do this on the roboRIO 439 for (VideoSink i : m_sinks.values()) { 440 int sink = i.getHandle(); 441 int sinkSource = CameraServerJNI.getSinkSource(sink); 442 if (source == sinkSource 443 && VideoSink.getKindFromInt(CameraServerJNI.getSinkKind(sink)) 444 == VideoSink.Kind.kMjpeg) { 445 // Add USB-only passthrough 446 String[] finalValues = Arrays.copyOf(values, values.length + 1); 447 int port = CameraServerJNI.getMjpegServerPort(sink); 448 finalValues[values.length] = makeStreamValue("172.22.11.2", port); 449 return finalValues; 450 } 451 } 452 } 453 454 return values; 455 } 456 457 /** Update list of stream URIs. */ 458 private static synchronized void updateStreamValues() { 459 // Over all the sinks... 460 for (VideoSink i : m_sinks.values()) { 461 int sink = i.getHandle(); 462 463 // Get the source's subtable (if none exists, we're done) 464 int source = 465 Objects.requireNonNullElseGet( 466 m_fixedSources.get(sink), () -> CameraServerJNI.getSinkSource(sink)); 467 468 if (source == 0) { 469 continue; 470 } 471 SourcePublisher publisher = m_publishers.get(source); 472 if (publisher != null) { 473 // Don't set stream values if this is a HttpCamera passthrough 474 if (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source)) 475 == VideoSource.Kind.kHttp) { 476 continue; 477 } 478 479 // Set table value 480 String[] values = getSinkStreamValues(sink); 481 if (values.length > 0) { 482 publisher.m_streamsPublisher.set(values); 483 } 484 } 485 } 486 487 // Over all the sources... 488 for (VideoSource i : m_sources.values()) { 489 int source = i.getHandle(); 490 491 // Get the source's subtable (if none exists, we're done) 492 SourcePublisher publisher = m_publishers.get(source); 493 if (publisher != null) { 494 // Set table value 495 String[] values = getSourceStreamValues(source); 496 if (values.length > 0) { 497 publisher.m_streamsPublisher.set(values); 498 } 499 } 500 } 501 } 502 503 /** Provide string description of pixel format. */ 504 private static String pixelFormatToString(PixelFormat pixelFormat) { 505 switch (pixelFormat) { 506 case kMJPEG: 507 return "MJPEG"; 508 case kYUYV: 509 return "YUYV"; 510 case kRGB565: 511 return "RGB565"; 512 case kBGR: 513 return "BGR"; 514 case kGray: 515 return "Gray"; 516 default: 517 return "Unknown"; 518 } 519 } 520 521 /** 522 * Provide string description of video mode. 523 * 524 * <p>The returned string is "{width}x{height} {format} {fps} fps". 525 */ 526 private static String videoModeToString(VideoMode mode) { 527 return mode.width 528 + "x" 529 + mode.height 530 + " " 531 + pixelFormatToString(mode.pixelFormat) 532 + " " 533 + mode.fps 534 + " fps"; 535 } 536 537 /** 538 * Get list of video modes for the given source handle. 539 * 540 * @param sourceHandle Source handle. 541 */ 542 private static String[] getSourceModeValues(int sourceHandle) { 543 VideoMode[] modes = CameraServerJNI.enumerateSourceVideoModes(sourceHandle); 544 String[] modeStrings = new String[modes.length]; 545 for (int i = 0; i < modes.length; i++) { 546 modeStrings[i] = videoModeToString(modes[i]); 547 } 548 return modeStrings; 549 } 550 551 private CameraServer() {} 552 553 /** 554 * Start automatically capturing images to send to the dashboard. 555 * 556 * <p>You should call this method to see a camera feed on the dashboard. If you also want to 557 * perform vision processing on the roboRIO, use getVideo() to get access to the camera images. 558 * 559 * <p>The first time this overload is called, it calls {@link #startAutomaticCapture(int)} with 560 * device 0, creating a camera named "USB Camera 0". Subsequent calls increment the device number 561 * (e.g. 1, 2, etc). 562 * 563 * @return The USB camera capturing images. 564 */ 565 public static UsbCamera startAutomaticCapture() { 566 UsbCamera camera = startAutomaticCapture(m_defaultUsbDevice.getAndIncrement()); 567 CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle()); 568 return camera; 569 } 570 571 /** 572 * Start automatically capturing images to send to the dashboard. 573 * 574 * <p>This overload calls {@link #startAutomaticCapture(String, int)} with a name of "USB Camera 575 * {dev}". 576 * 577 * @param dev The device number of the camera interface 578 * @return The USB camera capturing images. 579 */ 580 public static UsbCamera startAutomaticCapture(int dev) { 581 UsbCamera camera = new UsbCamera("USB Camera " + dev, dev); 582 startAutomaticCapture(camera); 583 CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle()); 584 return camera; 585 } 586 587 /** 588 * Start automatically capturing images to send to the dashboard. 589 * 590 * @param name The name to give the camera 591 * @param dev The device number of the camera interface 592 * @return The USB camera capturing images. 593 */ 594 public static UsbCamera startAutomaticCapture(String name, int dev) { 595 UsbCamera camera = new UsbCamera(name, dev); 596 startAutomaticCapture(camera); 597 CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle()); 598 return camera; 599 } 600 601 /** 602 * Start automatically capturing images to send to the dashboard. 603 * 604 * @param name The name to give the camera 605 * @param path The device path (e.g. "/dev/video0") of the camera 606 * @return The USB camera capturing images. 607 */ 608 public static UsbCamera startAutomaticCapture(String name, String path) { 609 UsbCamera camera = new UsbCamera(name, path); 610 startAutomaticCapture(camera); 611 CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle()); 612 return camera; 613 } 614 615 /** 616 * Start automatically capturing images to send to the dashboard from an existing camera. 617 * 618 * @param camera Camera 619 * @return The MJPEG server serving images from the given camera. 620 */ 621 public static MjpegServer startAutomaticCapture(VideoSource camera) { 622 addCamera(camera); 623 MjpegServer server = addServer("serve_" + camera.getName()); 624 server.setSource(camera); 625 return server; 626 } 627 628 /** 629 * Adds an Axis IP camera. 630 * 631 * <p>This overload calls {@link #addAxisCamera(String, String)} with name "Axis Camera". 632 * 633 * @param host Camera host IP or DNS name (e.g. "10.x.y.11") 634 * @return The Axis camera capturing images. 635 */ 636 public static AxisCamera addAxisCamera(String host) { 637 return addAxisCamera("Axis Camera", host); 638 } 639 640 /** 641 * Adds an Axis IP camera. 642 * 643 * <p>This overload calls {@link #addAxisCamera(String, String[])} with name "Axis Camera". 644 * 645 * @param hosts Array of Camera host IPs/DNS names 646 * @return The Axis camera capturing images. 647 */ 648 public static AxisCamera addAxisCamera(String[] hosts) { 649 return addAxisCamera("Axis Camera", hosts); 650 } 651 652 /** 653 * Adds an Axis IP camera. 654 * 655 * @param name The name to give the camera 656 * @param host Camera host IP or DNS name (e.g. "10.x.y.11") 657 * @return The Axis camera capturing images. 658 */ 659 public static AxisCamera addAxisCamera(String name, String host) { 660 AxisCamera camera = new AxisCamera(name, host); 661 // Create a passthrough MJPEG server for USB access 662 startAutomaticCapture(camera); 663 CameraServerSharedStore.getCameraServerShared().reportAxisCamera(camera.getHandle()); 664 return camera; 665 } 666 667 /** 668 * Adds an Axis IP camera. 669 * 670 * @param name The name to give the camera 671 * @param hosts Array of Camera host IPs/DNS names 672 * @return The Axis camera capturing images. 673 */ 674 public static AxisCamera addAxisCamera(String name, String[] hosts) { 675 AxisCamera camera = new AxisCamera(name, hosts); 676 // Create a passthrough MJPEG server for USB access 677 startAutomaticCapture(camera); 678 CameraServerSharedStore.getCameraServerShared().reportAxisCamera(camera.getHandle()); 679 return camera; 680 } 681 682 /** 683 * Adds a virtual camera for switching between two streams. Unlike the other addCamera methods, 684 * this returns a VideoSink rather than a VideoSource. Calling setSource() on the returned object 685 * can be used to switch the actual source of the stream. 686 * 687 * @param name The name to give the camera 688 * @return The MJPEG server serving images from the given camera. 689 */ 690 public static MjpegServer addSwitchedCamera(String name) { 691 // create a dummy CvSource 692 CvSource source = new CvSource(name, PixelFormat.kMJPEG, 160, 120, 30); 693 MjpegServer server = startAutomaticCapture(source); 694 synchronized (CameraServer.class) { 695 m_fixedSources.put(server.getHandle(), source.getHandle()); 696 } 697 698 return server; 699 } 700 701 /** 702 * Get OpenCV access to the primary camera feed. This allows you to get images from the camera for 703 * image processing on the roboRIO. 704 * 705 * <p>This is only valid to call after a camera feed has been added with startAutomaticCapture() 706 * or addServer(). 707 * 708 * @return OpenCV sink for the primary camera feed 709 */ 710 public static CvSink getVideo() { 711 VideoSource source; 712 synchronized (CameraServer.class) { 713 if (m_primarySourceName == null) { 714 throw new VideoException("no camera available"); 715 } 716 source = m_sources.get(m_primarySourceName); 717 } 718 if (source == null) { 719 throw new VideoException("no camera available"); 720 } 721 return getVideo(source); 722 } 723 724 /** 725 * Get OpenCV access to the specified camera. This allows you to get images from the camera for 726 * image processing on the roboRIO. 727 * 728 * @param camera Camera (e.g. as returned by startAutomaticCapture). 729 * @return OpenCV sink for the specified camera 730 */ 731 public static CvSink getVideo(VideoSource camera) { 732 String name = "opencv_" + camera.getName(); 733 734 synchronized (CameraServer.class) { 735 VideoSink sink = m_sinks.get(name); 736 if (sink != null) { 737 VideoSink.Kind kind = sink.getKind(); 738 if (kind != VideoSink.Kind.kCv) { 739 throw new VideoException("expected OpenCV sink, but got " + kind); 740 } 741 return (CvSink) sink; 742 } 743 } 744 745 CvSink newsink = new CvSink(name); 746 newsink.setSource(camera); 747 addServer(newsink); 748 return newsink; 749 } 750 751 /** 752 * Get OpenCV access to the specified camera. This allows you to get images from the camera for 753 * image processing on the roboRIO. 754 * 755 * @param camera Camera (e.g. as returned by startAutomaticCapture). 756 * @param pixelFormat Desired pixelFormat of the camera 757 * @return OpenCV sink for the specified camera 758 */ 759 public static CvSink getVideo(VideoSource camera, PixelFormat pixelFormat) { 760 String name = "opencv_" + camera.getName(); 761 762 synchronized (CameraServer.class) { 763 VideoSink sink = m_sinks.get(name); 764 if (sink != null) { 765 VideoSink.Kind kind = sink.getKind(); 766 if (kind != VideoSink.Kind.kCv) { 767 throw new VideoException("expected OpenCV sink, but got " + kind); 768 } 769 return (CvSink) sink; 770 } 771 } 772 773 CvSink newsink = new CvSink(name, pixelFormat); 774 newsink.setSource(camera); 775 addServer(newsink); 776 return newsink; 777 } 778 779 /** 780 * Get OpenCV access to the specified camera. This allows you to get images from the camera for 781 * image processing on the roboRIO. 782 * 783 * @param name Camera name 784 * @return OpenCV sink for the specified camera 785 */ 786 public static CvSink getVideo(String name) { 787 VideoSource source; 788 synchronized (CameraServer.class) { 789 source = m_sources.get(name); 790 if (source == null) { 791 throw new VideoException("could not find camera " + name); 792 } 793 } 794 return getVideo(source); 795 } 796 797 /** 798 * Create a MJPEG stream with OpenCV input. This can be called to pass custom annotated images to 799 * the dashboard. 800 * 801 * @param name Name to give the stream 802 * @param width Width of the image being sent 803 * @param height Height of the image being sent 804 * @return OpenCV source for the MJPEG stream 805 */ 806 public static CvSource putVideo(String name, int width, int height) { 807 CvSource source = new CvSource(name, PixelFormat.kMJPEG, width, height, 30); 808 startAutomaticCapture(source); 809 return source; 810 } 811 812 /** 813 * Adds a MJPEG server at the next available port. 814 * 815 * @param name Server name 816 * @return The MJPEG server 817 */ 818 public static MjpegServer addServer(String name) { 819 int port; 820 synchronized (CameraServer.class) { 821 port = m_nextPort; 822 m_nextPort++; 823 } 824 return addServer(name, port); 825 } 826 827 /** 828 * Adds a MJPEG server. 829 * 830 * @param name Server name 831 * @param port Server port 832 * @return The MJPEG server 833 */ 834 public static MjpegServer addServer(String name, int port) { 835 MjpegServer server = new MjpegServer(name, port); 836 addServer(server); 837 return server; 838 } 839 840 /** 841 * Adds an already created server. 842 * 843 * @param server Server 844 */ 845 public static void addServer(VideoSink server) { 846 synchronized (CameraServer.class) { 847 m_sinks.put(server.getName(), server); 848 } 849 } 850 851 /** 852 * Removes a server by name. 853 * 854 * @param name Server name 855 */ 856 public static void removeServer(String name) { 857 synchronized (CameraServer.class) { 858 m_sinks.remove(name); 859 } 860 } 861 862 /** 863 * Get server for the primary camera feed. 864 * 865 * <p>This is only valid to call after a camera feed has been added with startAutomaticCapture() 866 * or addServer(). 867 * 868 * @return The server for the primary camera feed 869 */ 870 public static VideoSink getServer() { 871 synchronized (CameraServer.class) { 872 if (m_primarySourceName == null) { 873 throw new VideoException("no camera available"); 874 } 875 return getServer("serve_" + m_primarySourceName); 876 } 877 } 878 879 /** 880 * Gets a server by name. 881 * 882 * @param name Server name 883 * @return The server 884 */ 885 public static VideoSink getServer(String name) { 886 synchronized (CameraServer.class) { 887 return m_sinks.get(name); 888 } 889 } 890 891 /** 892 * Adds an already created camera. 893 * 894 * @param camera Camera 895 */ 896 public static void addCamera(VideoSource camera) { 897 String name = camera.getName(); 898 synchronized (CameraServer.class) { 899 if (m_primarySourceName == null) { 900 m_primarySourceName = name; 901 } 902 m_sources.put(name, camera); 903 } 904 } 905 906 /** 907 * Removes a camera by name. 908 * 909 * @param name Camera name 910 */ 911 public static void removeCamera(String name) { 912 synchronized (CameraServer.class) { 913 m_sources.remove(name); 914 } 915 } 916}