Publishing and Subscribing to a Topic

Publishing to a Topic

In order to create a topic and publish values to it, it’s necessary to create a publisher.

NetworkTable publishers are represented as type-specific Publisher objects (e.g. BooleanPublisher: Java, C++, Python). Publishers are only active as long as the Publisher object exists. Typically you want to keep publishing longer than the local scope of a function, so it’s necessary to store the Publisher object somewhere longer term, e.g. in an instance variable. In Java, the close() method needs be called to stop publishing; in C++ this is handled by the destructor. C++ publishers are moveable and non-copyable. In Python the close() method should be called to stop publishing, but it will also be closed when the object is garbage collected.

In the handle-based APIs, there is only the non-type-specific NT_Publisher handle; the user is responsible for keeping track of the type of the publisher and using the correct type-specific set methods.

Publishing values is done via a set() operation. By default, this operation uses the current time, but a timestamp may optionally be specified. Specifying a timestamp can be useful when multiple values should have the same update timestamp. The timestamp units are integer microseconds (see example code for how to get a current timestamp that is consistent with the library).

public class Example {
  // the publisher is an instance variable so its lifetime matches that of the class
  final DoublePublisher dblPub;

  public Example(DoubleTopic dblTopic) {
    // start publishing; the return value must be retained (in this case, via
    // an instance variable)
    dblPub = dblTopic.publish();

    // publish options may be specified using PubSubOption
    dblPub = dblTopic.publish(PubSubOption.keepDuplicates(true));

    // publishEx provides additional options such as setting initial
    // properties and using a custom type string. Using a custom type string for
    // types other than raw and string is not recommended. The properties string
    // must be a JSON map.
    dblPub = dblTopic.publishEx("double", "{\"myprop\": 5}");
  }

  public void periodic() {
    // publish a default value
    dblPub.setDefault(0.0);

    // publish a value with current timestamp
    dblPub.set(1.0);
    dblPub.set(2.0, 0);  // 0 = use current time

    // publish a value with a specific timestamp; NetworkTablesJNI.now() can
    // be used to get the current time. On the roboRIO, this is the same as
    // the FPGA timestamp (e.g. RobotController.getFPGATime())
    long time = NetworkTablesJNI.now();
    dblPub.set(3.0, time);

    // publishers also implement the appropriate Consumer functional interface;
    // this example assumes void myFunc(DoubleConsumer func) exists
    myFunc(dblPub);
  }

  // often not required in robot code, unless this class doesn't exist for
  // the lifetime of the entire robot program, in which case close() needs to be
  // called to stop publishing
  public void close() {
    // stop publishing
    dblPub.close();
  }
}

Subscribing to a Topic

A subscriber receives value updates made to a topic. Similar to publishers, NetworkTable subscribers are represented as type-specific Subscriber classes (e.g. BooleanSubscriber: Java, C++, Python) that must be stored somewhere to continue subscribing.

Subscribers have a range of different ways to read received values. It’s possible to just read the most recent value using get(), read the most recent value, along with its timestamp, using getAtomic(), or get an array of all value changes since the last call using readQueue() or readQueueValues().

public class Example {
  // the subscriber is an instance variable so its lifetime matches that of the class
  final DoubleSubscriber dblSub;

  public Example(DoubleTopic dblTopic) {
    // start subscribing; the return value must be retained.
    // the parameter is the default value if no value is available when get() is called
    dblSub = dblTopic.subscribe(0.0);

    // subscribe options may be specified using PubSubOption
    dblSub =
        dblTopic.subscribe(0.0, PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10));

    // subscribeEx provides the options of using a custom type string.
    // Using a custom type string for types other than raw and string is not recommended.
    dblSub = dblTopic.subscribeEx("double", 0.0);
  }

  public void periodic() {
    // simple get of most recent value; if no value has been published,
    // returns the default value passed to the subscribe() function
    double val = dblSub.get();

    // get the most recent value; if no value has been published, returns
    // the passed-in default value
    double val = dblSub.get(-1.0);

    // subscribers also implement the appropriate Supplier interface, e.g. DoubleSupplier
    double val = dblSub.getAsDouble();

    // get the most recent value, along with its timestamp
    TimestampedDouble tsVal = dblSub.getAtomic();

    // read all value changes since the last call to readQueue/readQueueValues
    // readQueue() returns timestamps; readQueueValues() does not.
    TimestampedDouble[] tsUpdates = dblSub.readQueue();
    double[] valUpdates = dblSub.readQueueValues();
  }

  // often not required in robot code, unless this class doesn't exist for
  // the lifetime of the entire robot program, in which case close() needs to be
  // called to stop subscribing
  public void close() {
    // stop subscribing
    dblSub.close();
  }
}

Using Entry to Both Subscribe and Publish

An entry is a combined publisher and subscriber. The subscriber is always active, but the publisher is not created until a publish operation is performed (e.g. a value is “set”, aka published, on the entry). This may be more convenient than maintaining a separate publisher and subscriber. Similar to publishers and subscribers, NetworkTable entries are represented as type-specific Entry classes (e.g. BooleanEntry: Java, C++, Python) that must be retained to continue subscribing (and publishing).

public class Example {
  // the entry is an instance variable so its lifetime matches that of the class
  final DoubleEntry dblEntry;

  public Example(DoubleTopic dblTopic) {
    // start subscribing; the return value must be retained.
    // the parameter is the default value if no value is available when get() is called
    dblEntry = dblTopic.getEntry(0.0);

    // publish and subscribe options may be specified using PubSubOption
    dblEntry =
        dblTopic.getEntry(0.0, PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10));

    // getEntryEx provides the options of using a custom type string.
    // Using a custom type string for types other than raw and string is not recommended.
    dblEntry = dblTopic.getEntryEx("double", 0.0);
  }

  public void periodic() {
    // entries support all the same methods as subscribers:
    double val = dblEntry.get();
    double val = dblEntry.get(-1.0);
    double val = dblEntry.getAsDouble();
    TimestampedDouble tsVal = dblEntry.getAtomic();
    TimestampedDouble[] tsUpdates = dblEntry.readQueue();
    double[] valUpdates = dblEntry.readQueueValues();

    // entries also support all the same methods as publishers; the first time
    // one of these is called, an internal publisher is automatically created
    dblEntry.setDefault(0.0);
    dblEntry.set(1.0);
    dblEntry.set(2.0, 0);  // 0 = use current time
    long time = NetworkTablesJNI.now();
    dblEntry.set(3.0, time);
    myFunc(dblEntry);
  }

  public void unpublish() {
    // you can stop publishing while keeping the subscriber alive
    dblEntry.unpublish();
  }

  // often not required in robot code, unless this class doesn't exist for
  // the lifetime of the entire robot program, in which case close() needs to be
  // called to stop subscribing
  public void close() {
    // stop subscribing/publishing
    dblEntry.close();
  }
}

Using GenericEntry, GenericPublisher, and GenericSubscriber

For the most robust code, using the type-specific Publisher, Subscriber, and Entry classes is recommended, but in some cases it may be easier to write code that uses type-specific get and set function calls instead of having the NetworkTables type be exposed via the class (object) type. The GenericPublisher (Java, C++, Python), GenericSubscriber (Java, C++, Python), and GenericEntry (Java, C++, Python) classes enable this approach.

public class Example {
  // the entry is an instance variable so its lifetime matches that of the class
  final GenericPublisher pub;
  final GenericSubscriber sub;
  final GenericEntry entry;

  public Example(Topic topic) {
    // start subscribing; the return value must be retained.
    // when publishing, a type string must be provided
    pub = topic.genericPublish("double");

    // subscribing can optionally include a type string
    // unlike type-specific subscribers, no default value is provided
    sub = topic.genericSubscribe();
    sub = topic.genericSubscribe("double");

    // when getting an entry, the type string is also optional; if not provided
    // the publisher data type will be determined by the first publisher-creating call
    entry = topic.getGenericEntry();
    entry = topic.getGenericEntry("double");

    // publish and subscribe options may be specified using PubSubOption
    pub = topic.genericPublish("double",
        PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10));
    sub =
        topic.genericSubscribe(PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10));
    entry =
        topic.getGenericEntry(PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10));

    // genericPublishEx provides the option of setting initial properties.
    pub = topic.genericPublishEx("double", "{\"retained\": true}",
        PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10));
  }

  public void periodic() {
    // generic subscribers and entries have typed get operations; a default must be provided
    double val = sub.getDouble(-1.0);
    double val = entry.getDouble(-1.0);

    // they also support an untyped get (also meets Supplier<NetworkTableValue> interface)
    NetworkTableValue val = sub.get();
    NetworkTableValue val = entry.get();

    // they also support readQueue
    NetworkTableValue[] updates = sub.readQueue();
    NetworkTableValue[] updates = entry.readQueue();

    // publishers and entries have typed set operations; these return false if the
    // topic already exists with a mismatched type
    boolean success = pub.setDefaultDouble(1.0);
    boolean success = pub.setBoolean(true);

    // they also implement a generic set and Consumer<NetworkTableValue> interface
    boolean success = entry.set(NetworkTableValue.makeDouble(...));
    boolean success = entry.accept(NetworkTableValue.makeDouble(...));
  }

  public void unpublish() {
    // you can stop publishing an entry while keeping the subscriber alive
    entry.unpublish();
  }

  // often not required in robot code, unless this class doesn't exist for
  // the lifetime of the entire robot program, in which case close() needs to be
  // called to stop subscribing/publishing
  public void close() {
    pub.close();
    sub.close();
    entry.close();
  }
}

Subscribing to Multiple Topics

While in most cases it’s only necessary to subscribe to individual topics, it is sometimes useful (e.g. in dashboard applications) to subscribe and get value updates for changes to multiple topics. Listeners (see Listening for Changes) can be used directly, but creating a MultiSubscriber (Java, C++) allows specifying subscription options and reusing the same subscriber for multiple listeners.

public class Example {
  // the subscriber is an instance variable so its lifetime matches that of the class
  final MultiSubscriber multiSub;
  final NetworkTableListenerPoller poller;

  public Example(NetworkTableInstance inst) {
    // start subscribing; the return value must be retained.
    // provide an array of topic name prefixes
    multiSub = new MultiSubscriber(inst, new String[] {"/table1/", "/table2/"});

    // subscribe options may be specified using PubSubOption
    multiSub = new MultiSubscriber(inst, new String[] {"/table1/", "/table2/"},
        PubSubOption.keepDuplicates(true));

    // to get value updates from a MultiSubscriber, it's necessary to create a listener
    // (see the listener documentation for more details)
    poller = new NetworkTableListenerPoller(inst);
    poller.addListener(multiSub, EnumSet.of(NetworkTableEvent.Kind.kValueAll));
  }

  public void periodic() {
    // read value events
    NetworkTableEvent[] events = poller.readQueue();

    for (NetworkTableEvent event : events) {
      NetworkTableValue value = event.valueData.value;
    }
  }

  // often not required in robot code, unless this class doesn't exist for
  // the lifetime of the entire robot program, in which case close() needs to be
  // called to stop subscribing
  public void close() {
    // close listener
    poller.close();
    // stop subscribing
    multiSub.close();
  }
}

Publish/Subscribe Options

Publishers and subscribers have various options that affect their behavior. Options can only be set at the creation of the publisher, subscriber, or entry. Options set on an entry affect both the publisher and subscriber portions of the entry. The above examples show how options can be set when creating a publisher or subscriber.

Subscriber options:

  • pollStorage: Polling storage size for a subscription. Specifies the maximum number of updates NetworkTables should store between calls to the subscriber’s readQueue() function. If zero, defaults to 1 if sendAll is false, 20 if sendAll is true.

  • topicsOnly: Don’t send value changes, only topic announcements. Defaults to false. As a client doesn’t get topic announcements for topics it is not subscribed to, this option may be used with MultiSubscriber to get topic announcements for a particular topic name prefix, without also getting all value changes.

  • excludePublisher: Used to exclude a single publisher’s updates from being queued to the subscriber’s readQueue() function. This is primarily useful in scenarios where you don’t want local value updates to be “echoed back” to a local subscriber. Regardless of this setting, the topic value is updated–this only affects readQueue() on this subscriber.

  • disableRemote: If true, remote value updates are not queued for readQueue(). Defaults to false. Regardless of this setting, the topic value is updated–this only affects readQueue() on this subscriber.

  • disableLocal: If true, local value updates are not queued for readQueue(). Defaults to false. Regardless of this setting, the topic value is updated–this only affects readQueue() on this subscriber.

Subscriber and publisher options:

  • periodic: How frequently changes will be sent over the network, in seconds. NetworkTables may send more frequently than this (e.g. use a combined minimum period for all values) or apply a restricted range to this value. The default is 0.1 seconds. For publishers, it specifies how frequently local changes should be sent over the network; for subscribers, it is a request to the server to send server changes at the requested rate. Note that regardless of the setting of this option, only value changes are sent, unless the keepDuplicates option is set.

  • sendAll: If true, send all value changes over the network. Defaults to false. As with periodic, this is a request to the server for subscribers and a behavior change for publishers.

  • keepDuplicates: If true, preserves duplicate value changes (rather than ignoring them). Defaults to false. As with periodic, this is a request to the server for subscribers and a behavior change for publishers.

Entry options:

  • excludeSelf: Provides the same behavior as excludePublisher for the entry’s internal publisher. Defaults to false.

NetworkTableEntry

NetworkTableEntry (Java, C++, Python) is a class that exists for backwards compatibility. New code should prefer using type-specific Publisher and Subscriber classes, or GenericEntry if non-type-specific access is needed.

It is similar to GenericEntry in that it supports both publishing and subscribing in a single object. However, unlike GenericEntry, NetworkTableEntry is not released (e.g. unsubscribes/unpublishes) if close() is called (in Java) or the object is destroyed (in C++); instead, it operates similar to Topic, in that only a single NetworkTableEntry exists for each topic and it lasts for the lifetime of the instance.