Skip to content

Commit 57e1075

Browse files
authored
[wpilib] Add usage reporting for dashboards as instances (#7294)
Detects dashboards based on network tables client identity.
1 parent 8ec22b7 commit 57e1075

File tree

7 files changed

+175
-0
lines changed

7 files changed

+175
-0
lines changed

hal/src/generate/Instances.txt

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,3 +52,12 @@ kKinematics_SwerveDrive = 3
5252
kOdometry_DifferentialDrive = 1
5353
kOdometry_MecanumDrive = 2
5454
kOdometry_SwerveDrive = 3
55+
kDashboard_Unknown = 1
56+
kDashboard_Glass = 2
57+
kDashboard_SmartDashboard = 3
58+
kDashboard_Shuffleboard = 4
59+
kDashboard_Elastic = 5
60+
kDashboard_LabVIEW = 6
61+
kDashboard_AdvantageScope = 7
62+
kDashboard_QFRCDashboard = 8
63+
kDashboard_FRCWebComponents = 9

hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java

Lines changed: 18 additions & 0 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

hal/src/generated/main/native/include/hal/FRCUsageReporting.h

Lines changed: 9 additions & 0 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

hal/src/generated/main/native/include/hal/UsageReporting.h

Lines changed: 9 additions & 0 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

wpilibc/src/main/native/cppcs/RobotBase.cpp

Lines changed: 62 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,11 +10,13 @@
1010

1111
#include <cstdio>
1212
#include <memory>
13+
#include <string>
1314
#include <utility>
1415

1516
#include <cameraserver/CameraServerShared.h>
1617
#include <hal/FRCUsageReporting.h>
1718
#include <hal/HALBase.h>
19+
#include <networktables/NetworkTable.h>
1820
#include <networktables/NetworkTableInstance.h>
1921
#include <wpi/print.h>
2022
#include <wpi/timestamp.h>
@@ -249,6 +251,66 @@ RobotBase::RobotBase() {
249251
}
250252
}
251253

254+
connListenerHandle = inst.AddConnectionListener(false, [&](const nt::Event&
255+
event) {
256+
if (event.Is(nt::EventFlags::kConnected)) {
257+
if (event.GetConnectionInfo()->remote_id.starts_with("glass")) {
258+
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
259+
HALUsageReporting::kDashboard_Glass);
260+
m_dashboardDetected = true;
261+
} else if (event.GetConnectionInfo()->remote_id.starts_with(
262+
"SmartDashboard")) {
263+
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
264+
HALUsageReporting::kDashboard_SmartDashboard);
265+
m_dashboardDetected = true;
266+
} else if (event.GetConnectionInfo()->remote_id.starts_with(
267+
"shuffleboard")) {
268+
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
269+
HALUsageReporting::kDashboard_Shuffleboard);
270+
m_dashboardDetected = true;
271+
} else if (event.GetConnectionInfo()->remote_id.starts_with("elastic") ||
272+
event.GetConnectionInfo()->remote_id.starts_with("Elastic")) {
273+
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
274+
HALUsageReporting::kDashboard_Elastic);
275+
m_dashboardDetected = true;
276+
} else if (event.GetConnectionInfo()->remote_id.starts_with(
277+
"Dashboard")) {
278+
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
279+
HALUsageReporting::kDashboard_LabVIEW);
280+
m_dashboardDetected = true;
281+
} else if (event.GetConnectionInfo()->remote_id.starts_with(
282+
"AdvantageScope")) {
283+
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
284+
HALUsageReporting::kDashboard_AdvantageScope);
285+
m_dashboardDetected = true;
286+
} else if (event.GetConnectionInfo()->remote_id.starts_with(
287+
"QFRCDashboard")) {
288+
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
289+
HALUsageReporting::kDashboard_QFRCDashboard);
290+
m_dashboardDetected = true;
291+
} else if (event.GetConnectionInfo()->remote_id.starts_with(
292+
"FRC Web Components")) {
293+
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
294+
HALUsageReporting::kDashboard_FRCWebComponents);
295+
m_dashboardDetected = true;
296+
} else {
297+
if (!m_dashboardDetected) {
298+
size_t delim = event.GetConnectionInfo()->remote_id.find('@');
299+
if (delim != std::string::npos) {
300+
HAL_Report(
301+
HALUsageReporting::kResourceType_Dashboard,
302+
HALUsageReporting::kDashboard_Unknown, 0,
303+
event.GetConnectionInfo()->remote_id.substr(0, delim).c_str());
304+
} else {
305+
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
306+
HALUsageReporting::kDashboard_Unknown, 0,
307+
event.GetConnectionInfo()->remote_id.c_str());
308+
}
309+
}
310+
}
311+
}
312+
});
313+
252314
SmartDashboard::init();
253315

254316
if constexpr (!IsSimulation()) {

wpilibc/src/main/native/include/frc/RobotBase.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
#include <hal/DriverStation.h>
1111
#include <hal/HALBase.h>
1212
#include <hal/Main.h>
13+
#include <networktables/NetworkTable.h>
1314
#include <wpi/RuntimeCheck.h>
1415
#include <wpi/condition_variable.h>
1516
#include <wpi/mutex.h>
@@ -274,6 +275,8 @@ class RobotBase {
274275
RobotBase& operator=(RobotBase&&) = default;
275276

276277
static std::thread::id m_threadId;
278+
NT_Listener connListenerHandle;
279+
bool m_dashboardDetected = false;
277280
};
278281

279282
} // namespace frc

wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java

Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
import edu.wpi.first.math.MathSharedStore;
1515
import edu.wpi.first.math.MathUsageId;
1616
import edu.wpi.first.networktables.MultiSubscriber;
17+
import edu.wpi.first.networktables.NetworkTableEvent;
1718
import edu.wpi.first.networktables.NetworkTableInstance;
1819
import edu.wpi.first.util.WPIUtilJNI;
1920
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
@@ -43,6 +44,10 @@ public abstract class RobotBase implements AutoCloseable {
4344

4445
private final MultiSubscriber m_suball;
4546

47+
private final int m_connListenerHandle;
48+
49+
private boolean m_dashboardDetected;
50+
4651
private static void setupCameraServerShared() {
4752
CameraServerShared shared =
4853
new CameraServerShared() {
@@ -158,6 +163,65 @@ protected RobotBase() {
158163
System.err.println("timed out while waiting for NT server to start");
159164
}
160165

166+
m_connListenerHandle =
167+
inst.addConnectionListener(
168+
false,
169+
event -> {
170+
if (event.is(NetworkTableEvent.Kind.kConnected)) {
171+
if (event.connInfo.remote_id.startsWith("glass")) {
172+
HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Glass);
173+
m_dashboardDetected = true;
174+
} else if (event.connInfo.remote_id.startsWith("SmartDashboard")) {
175+
HAL.report(
176+
tResourceType.kResourceType_Dashboard, tInstances.kDashboard_SmartDashboard);
177+
m_dashboardDetected = true;
178+
} else if (event.connInfo.remote_id.startsWith("shuffleboard")) {
179+
HAL.report(
180+
tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Shuffleboard);
181+
m_dashboardDetected = true;
182+
} else if (event.connInfo.remote_id.startsWith("elastic")
183+
|| event.connInfo.remote_id.startsWith("Elastic")) {
184+
HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Elastic);
185+
m_dashboardDetected = true;
186+
} else if (event.connInfo.remote_id.startsWith("Dashboard")) {
187+
HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_LabVIEW);
188+
m_dashboardDetected = true;
189+
} else if (event.connInfo.remote_id.startsWith("AdvantageScope")) {
190+
HAL.report(
191+
tResourceType.kResourceType_Dashboard, tInstances.kDashboard_AdvantageScope);
192+
m_dashboardDetected = true;
193+
} else if (event.connInfo.remote_id.startsWith("QFRCDashboard")) {
194+
HAL.report(
195+
tResourceType.kResourceType_Dashboard, tInstances.kDashboard_QFRCDashboard);
196+
m_dashboardDetected = true;
197+
} else if (event.connInfo.remote_id.startsWith("FRC Web Components")) {
198+
HAL.report(
199+
tResourceType.kResourceType_Dashboard,
200+
tInstances.kDashboard_FRCWebComponents);
201+
m_dashboardDetected = true;
202+
} else {
203+
// Only report unknown if there wasn't another dashboard already reported
204+
// (unknown could also be another device)
205+
if (!m_dashboardDetected) {
206+
int delim = event.connInfo.remote_id.indexOf('@');
207+
if (delim != -1) {
208+
HAL.report(
209+
tResourceType.kResourceType_Dashboard,
210+
tInstances.kDashboard_Unknown,
211+
0,
212+
event.connInfo.remote_id.substring(0, delim));
213+
} else {
214+
HAL.report(
215+
tResourceType.kResourceType_Dashboard,
216+
tInstances.kDashboard_Unknown,
217+
0,
218+
event.connInfo.remote_id);
219+
}
220+
}
221+
}
222+
}
223+
});
224+
161225
LiveWindow.setEnabled(false);
162226
Shuffleboard.disableActuatorWidgets();
163227
}
@@ -174,6 +238,7 @@ public static long getMainThreadId() {
174238
@Override
175239
public void close() {
176240
m_suball.close();
241+
NetworkTableInstance.getDefault().removeListener(m_connListenerHandle);
177242
}
178243

179244
/**

0 commit comments

Comments
 (0)