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.livewindow; 006 007import edu.wpi.first.networktables.BooleanPublisher; 008import edu.wpi.first.networktables.NetworkTable; 009import edu.wpi.first.networktables.NetworkTableInstance; 010import edu.wpi.first.networktables.StringPublisher; 011import edu.wpi.first.networktables.StringTopic; 012import edu.wpi.first.util.sendable.Sendable; 013import edu.wpi.first.util.sendable.SendableRegistry; 014import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl; 015 016/** 017 * The LiveWindow class is the public interface for putting sensors and actuators on the LiveWindow. 018 */ 019public final class LiveWindow { 020 private static class Component implements AutoCloseable { 021 @Override 022 public void close() { 023 if (m_namePub != null) { 024 m_namePub.close(); 025 m_namePub = null; 026 } 027 if (m_typePub != null) { 028 m_typePub.close(); 029 m_typePub = null; 030 } 031 } 032 033 boolean m_firstTime = true; 034 boolean m_telemetryEnabled; 035 StringPublisher m_namePub; 036 StringPublisher m_typePub; 037 } 038 039 private static final int dataHandle = SendableRegistry.getDataHandle(); 040 private static final NetworkTable liveWindowTable = 041 NetworkTableInstance.getDefault().getTable("LiveWindow"); 042 private static final NetworkTable statusTable = liveWindowTable.getSubTable(".status"); 043 private static final BooleanPublisher enabledPub = 044 statusTable.getBooleanTopic("LW Enabled").publish(); 045 private static boolean startLiveWindow; 046 private static boolean liveWindowEnabled; 047 private static boolean telemetryEnabled; 048 049 private static Runnable enabledListener; 050 private static Runnable disabledListener; 051 052 static { 053 SendableRegistry.setLiveWindowBuilderFactory(() -> new SendableBuilderImpl()); 054 enabledPub.set(false); 055 } 056 057 private static Component getOrAdd(Sendable sendable) { 058 Component data = (Component) SendableRegistry.getData(sendable, dataHandle); 059 if (data == null) { 060 data = new Component(); 061 SendableRegistry.setData(sendable, dataHandle, data); 062 } 063 return data; 064 } 065 066 private LiveWindow() { 067 throw new UnsupportedOperationException("This is a utility class!"); 068 } 069 070 public static synchronized void setEnabledListener(Runnable runnable) { 071 enabledListener = runnable; 072 } 073 074 public static synchronized void setDisabledListener(Runnable runnable) { 075 disabledListener = runnable; 076 } 077 078 public static synchronized boolean isEnabled() { 079 return liveWindowEnabled; 080 } 081 082 /** 083 * Set the enabled state of LiveWindow. 084 * 085 * <p>If it's being enabled, turn off the scheduler and remove all the commands from the queue and 086 * enable all the components registered for LiveWindow. If it's being disabled, stop all the 087 * registered components and re-enable the scheduler. 088 * 089 * <p>TODO: add code to disable PID loops when enabling LiveWindow. The commands should re-enable 090 * the PID loops themselves when they get rescheduled. This prevents arms from starting to move 091 * around, etc. after a period of adjusting them in LiveWindow mode. 092 * 093 * @param enabled True to enable LiveWindow. 094 */ 095 public static synchronized void setEnabled(boolean enabled) { 096 if (liveWindowEnabled != enabled) { 097 startLiveWindow = enabled; 098 liveWindowEnabled = enabled; 099 updateValues(); // Force table generation now to make sure everything is defined 100 if (enabled) { 101 System.out.println("Starting live window mode."); 102 if (enabledListener != null) { 103 enabledListener.run(); 104 } 105 } else { 106 System.out.println("stopping live window mode."); 107 SendableRegistry.foreachLiveWindow( 108 dataHandle, 109 cbdata -> { 110 ((SendableBuilderImpl) cbdata.builder).stopLiveWindowMode(); 111 }); 112 if (disabledListener != null) { 113 disabledListener.run(); 114 } 115 } 116 enabledPub.set(enabled); 117 } 118 } 119 120 /** 121 * Enable telemetry for a single component. 122 * 123 * @param sendable component 124 */ 125 public static synchronized void enableTelemetry(Sendable sendable) { 126 // Re-enable global setting in case disableAllTelemetry() was called. 127 telemetryEnabled = true; 128 getOrAdd(sendable).m_telemetryEnabled = true; 129 } 130 131 /** 132 * Disable telemetry for a single component. 133 * 134 * @param sendable component 135 */ 136 public static synchronized void disableTelemetry(Sendable sendable) { 137 getOrAdd(sendable).m_telemetryEnabled = false; 138 } 139 140 /** Disable ALL telemetry. */ 141 public static synchronized void disableAllTelemetry() { 142 telemetryEnabled = false; 143 SendableRegistry.foreachLiveWindow( 144 dataHandle, 145 cbdata -> { 146 if (cbdata.data == null) { 147 cbdata.data = new Component(); 148 } 149 ((Component) cbdata.data).m_telemetryEnabled = false; 150 }); 151 } 152 153 /** Enable ALL telemetry. */ 154 public static synchronized void enableAllTelemetry() { 155 telemetryEnabled = true; 156 SendableRegistry.foreachLiveWindow( 157 dataHandle, 158 cbdata -> { 159 if (cbdata.data == null) { 160 cbdata.data = new Component(); 161 } 162 ((Component) cbdata.data).m_telemetryEnabled = true; 163 }); 164 } 165 166 /** 167 * Tell all the sensors to update (send) their values. 168 * 169 * <p>Actuators are handled through callbacks on their value changing from the SmartDashboard 170 * widgets. 171 */ 172 public static synchronized void updateValues() { 173 // Only do this if either LiveWindow mode or telemetry is enabled. 174 if (!liveWindowEnabled && !telemetryEnabled) { 175 return; 176 } 177 178 SendableRegistry.foreachLiveWindow( 179 dataHandle, 180 cbdata -> { 181 if (cbdata.sendable == null || cbdata.parent != null) { 182 return; 183 } 184 185 if (cbdata.data == null) { 186 cbdata.data = new Component(); 187 } 188 189 Component component = (Component) cbdata.data; 190 191 if (!liveWindowEnabled && !component.m_telemetryEnabled) { 192 return; 193 } 194 195 if (component.m_firstTime) { 196 // By holding off creating the NetworkTable entries, it allows the 197 // components to be redefined. This allows default sensor and actuator 198 // values to be created that are replaced with the custom names from 199 // users calling setName. 200 if (cbdata.name.isEmpty()) { 201 return; 202 } 203 NetworkTable ssTable = liveWindowTable.getSubTable(cbdata.subsystem); 204 NetworkTable table; 205 // Treat name==subsystem as top level of subsystem 206 if (cbdata.name.equals(cbdata.subsystem)) { 207 table = ssTable; 208 } else { 209 table = ssTable.getSubTable(cbdata.name); 210 } 211 component.m_namePub = new StringTopic(table.getTopic(".name")).publish(); 212 component.m_namePub.set(cbdata.name); 213 ((SendableBuilderImpl) cbdata.builder).setTable(table); 214 cbdata.sendable.initSendable(cbdata.builder); 215 component.m_typePub = new StringTopic(ssTable.getTopic(".type")).publish(); 216 component.m_typePub.set("LW Subsystem"); 217 218 component.m_firstTime = false; 219 } 220 221 if (startLiveWindow) { 222 ((SendableBuilderImpl) cbdata.builder).startLiveWindowMode(); 223 } 224 cbdata.builder.update(); 225 }); 226 227 startLiveWindow = false; 228 } 229}