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