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.wpilibj.smartdashboard;
006
007import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
008
009import edu.wpi.first.networktables.NTSendable;
010import edu.wpi.first.networktables.NTSendableBuilder;
011import edu.wpi.first.networktables.NetworkTableEntry;
012import edu.wpi.first.util.sendable.SendableRegistry;
013import java.util.ArrayList;
014import java.util.LinkedHashMap;
015import java.util.List;
016import java.util.Map;
017import java.util.concurrent.atomic.AtomicInteger;
018import java.util.concurrent.locks.ReentrantLock;
019
020/**
021 * The {@link SendableChooser} class is a useful tool for presenting a selection of options to the
022 * {@link SmartDashboard}.
023 *
024 * <p>For instance, you may wish to be able to select between multiple autonomous modes. You can do
025 * this by putting every possible Command you want to run as an autonomous into a {@link
026 * SendableChooser} and then put it into the {@link SmartDashboard} to have a list of options appear
027 * on the laptop. Once autonomous starts, simply ask the {@link SendableChooser} what the selected
028 * value is.
029 *
030 * @param <V> The type of the values to be stored
031 */
032public class SendableChooser<V> implements NTSendable, AutoCloseable {
033  /** The key for the default value. */
034  private static final String DEFAULT = "default";
035  /** The key for the selected option. */
036  private static final String SELECTED = "selected";
037  /** The key for the active option. */
038  private static final String ACTIVE = "active";
039  /** The key for the option array. */
040  private static final String OPTIONS = "options";
041  /** The key for the instance number. */
042  private static final String INSTANCE = ".instance";
043  /** A map linking strings to the objects the represent. */
044  private final Map<String, V> m_map = new LinkedHashMap<>();
045
046  private String m_defaultChoice = "";
047  private final int m_instance;
048  private static final AtomicInteger s_instances = new AtomicInteger();
049
050  /** Instantiates a {@link SendableChooser}. */
051  public SendableChooser() {
052    m_instance = s_instances.getAndIncrement();
053    SendableRegistry.add(this, "SendableChooser", m_instance);
054  }
055
056  @Override
057  public void close() {
058    SendableRegistry.remove(this);
059  }
060
061  /**
062   * Adds the given object to the list of options. On the {@link SmartDashboard} on the desktop, the
063   * object will appear as the given name.
064   *
065   * @param name the name of the option
066   * @param object the option
067   */
068  public void addOption(String name, V object) {
069    m_map.put(name, object);
070  }
071
072  /**
073   * Adds the given object to the list of options.
074   *
075   * @param name the name of the option
076   * @param object the option
077   * @deprecated Use {@link #addOption(String, Object)} instead.
078   */
079  @Deprecated
080  public void addObject(String name, V object) {
081    addOption(name, object);
082  }
083
084  /**
085   * Adds the given object to the list of options and marks it as the default. Functionally, this is
086   * very close to {@link #addOption(String, Object)} except that it will use this as the default
087   * option if none other is explicitly selected.
088   *
089   * @param name the name of the option
090   * @param object the option
091   */
092  public void setDefaultOption(String name, V object) {
093    requireNonNullParam(name, "name", "setDefaultOption");
094
095    m_defaultChoice = name;
096    addOption(name, object);
097  }
098
099  /**
100   * Adds the given object to the list of options and marks it as the default.
101   *
102   * @param name the name of the option
103   * @param object the option
104   * @deprecated Use {@link #setDefaultOption(String, Object)} instead.
105   */
106  @Deprecated
107  public void addDefault(String name, V object) {
108    setDefaultOption(name, object);
109  }
110
111  /**
112   * Returns the selected option. If there is none selected, it will return the default. If there is
113   * none selected and no default, then it will return {@code null}.
114   *
115   * @return the option selected
116   */
117  public V getSelected() {
118    m_mutex.lock();
119    try {
120      if (m_selected != null) {
121        return m_map.get(m_selected);
122      } else {
123        return m_map.get(m_defaultChoice);
124      }
125    } finally {
126      m_mutex.unlock();
127    }
128  }
129
130  private String m_selected;
131  private final List<NetworkTableEntry> m_activeEntries = new ArrayList<>();
132  private final ReentrantLock m_mutex = new ReentrantLock();
133
134  @Override
135  public void initSendable(NTSendableBuilder builder) {
136    builder.setSmartDashboardType("String Chooser");
137    builder.getEntry(INSTANCE).setDouble(m_instance);
138    builder.addStringProperty(DEFAULT, () -> m_defaultChoice, null);
139    builder.addStringArrayProperty(OPTIONS, () -> m_map.keySet().toArray(new String[0]), null);
140    builder.addStringProperty(
141        ACTIVE,
142        () -> {
143          m_mutex.lock();
144          try {
145            if (m_selected != null) {
146              return m_selected;
147            } else {
148              return m_defaultChoice;
149            }
150          } finally {
151            m_mutex.unlock();
152          }
153        },
154        null);
155    m_mutex.lock();
156    try {
157      m_activeEntries.add(builder.getEntry(ACTIVE));
158    } finally {
159      m_mutex.unlock();
160    }
161    builder.addStringProperty(
162        SELECTED,
163        null,
164        val -> {
165          m_mutex.lock();
166          try {
167            m_selected = val;
168            for (NetworkTableEntry entry : m_activeEntries) {
169              entry.setString(val);
170            }
171          } finally {
172            m_mutex.unlock();
173          }
174        });
175  }
176}