[wpilib] Add usage reporting for dashboards as instances (#7294)

Detects dashboards based on network tables client identity.
This commit is contained in:
sciencewhiz
2024-11-18 09:16:29 -08:00
committed by GitHub
parent 8ec22b7d5c
commit 57e10755fd
7 changed files with 175 additions and 0 deletions

View File

@@ -52,3 +52,12 @@ kKinematics_SwerveDrive = 3
kOdometry_DifferentialDrive = 1
kOdometry_MecanumDrive = 2
kOdometry_SwerveDrive = 3
kDashboard_Unknown = 1
kDashboard_Glass = 2
kDashboard_SmartDashboard = 3
kDashboard_Shuffleboard = 4
kDashboard_Elastic = 5
kDashboard_LabVIEW = 6
kDashboard_AdvantageScope = 7
kDashboard_QFRCDashboard = 8
kDashboard_FRCWebComponents = 9

View File

@@ -369,6 +369,24 @@ public final class FRCNetComm {
public static final int kOdometry_MecanumDrive = 2;
/** kOdometry_SwerveDrive = 3. */
public static final int kOdometry_SwerveDrive = 3;
/** kDashboard_Unknown = 1. */
public static final int kDashboard_Unknown = 1;
/** kDashboard_Glass = 2. */
public static final int kDashboard_Glass = 2;
/** kDashboard_SmartDashboard = 3. */
public static final int kDashboard_SmartDashboard = 3;
/** kDashboard_Shuffleboard = 4. */
public static final int kDashboard_Shuffleboard = 4;
/** kDashboard_Elastic = 5. */
public static final int kDashboard_Elastic = 5;
/** kDashboard_LabVIEW = 6. */
public static final int kDashboard_LabVIEW = 6;
/** kDashboard_AdvantageScope = 7. */
public static final int kDashboard_AdvantageScope = 7;
/** kDashboard_QFRCDashboard = 8. */
public static final int kDashboard_QFRCDashboard = 8;
/** kDashboard_FRCWebComponents = 9. */
public static final int kDashboard_FRCWebComponents = 9;
}
/** Utility class. */

View File

@@ -223,6 +223,15 @@ namespace HALUsageReporting {
kOdometry_DifferentialDrive = 1,
kOdometry_MecanumDrive = 2,
kOdometry_SwerveDrive = 3,
kDashboard_Unknown = 1,
kDashboard_Glass = 2,
kDashboard_SmartDashboard = 3,
kDashboard_Shuffleboard = 4,
kDashboard_Elastic = 5,
kDashboard_LabVIEW = 6,
kDashboard_AdvantageScope = 7,
kDashboard_QFRCDashboard = 8,
kDashboard_FRCWebComponents = 9,
};
}
#endif

View File

@@ -196,6 +196,15 @@ typedef enum
kOdometry_DifferentialDrive = 1,
kOdometry_MecanumDrive = 2,
kOdometry_SwerveDrive = 3,
kDashboard_Unknown = 1,
kDashboard_Glass = 2,
kDashboard_SmartDashboard = 3,
kDashboard_Shuffleboard = 4,
kDashboard_Elastic = 5,
kDashboard_LabVIEW = 6,
kDashboard_AdvantageScope = 7,
kDashboard_QFRCDashboard = 8,
kDashboard_FRCWebComponents = 9,
} tInstances;
/**

View File

@@ -10,11 +10,13 @@
#include <cstdio>
#include <memory>
#include <string>
#include <utility>
#include <cameraserver/CameraServerShared.h>
#include <hal/FRCUsageReporting.h>
#include <hal/HALBase.h>
#include <networktables/NetworkTable.h>
#include <networktables/NetworkTableInstance.h>
#include <wpi/print.h>
#include <wpi/timestamp.h>
@@ -249,6 +251,66 @@ RobotBase::RobotBase() {
}
}
connListenerHandle = inst.AddConnectionListener(false, [&](const nt::Event&
event) {
if (event.Is(nt::EventFlags::kConnected)) {
if (event.GetConnectionInfo()->remote_id.starts_with("glass")) {
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
HALUsageReporting::kDashboard_Glass);
m_dashboardDetected = true;
} else if (event.GetConnectionInfo()->remote_id.starts_with(
"SmartDashboard")) {
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
HALUsageReporting::kDashboard_SmartDashboard);
m_dashboardDetected = true;
} else if (event.GetConnectionInfo()->remote_id.starts_with(
"shuffleboard")) {
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
HALUsageReporting::kDashboard_Shuffleboard);
m_dashboardDetected = true;
} else if (event.GetConnectionInfo()->remote_id.starts_with("elastic") ||
event.GetConnectionInfo()->remote_id.starts_with("Elastic")) {
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
HALUsageReporting::kDashboard_Elastic);
m_dashboardDetected = true;
} else if (event.GetConnectionInfo()->remote_id.starts_with(
"Dashboard")) {
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
HALUsageReporting::kDashboard_LabVIEW);
m_dashboardDetected = true;
} else if (event.GetConnectionInfo()->remote_id.starts_with(
"AdvantageScope")) {
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
HALUsageReporting::kDashboard_AdvantageScope);
m_dashboardDetected = true;
} else if (event.GetConnectionInfo()->remote_id.starts_with(
"QFRCDashboard")) {
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
HALUsageReporting::kDashboard_QFRCDashboard);
m_dashboardDetected = true;
} else if (event.GetConnectionInfo()->remote_id.starts_with(
"FRC Web Components")) {
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
HALUsageReporting::kDashboard_FRCWebComponents);
m_dashboardDetected = true;
} else {
if (!m_dashboardDetected) {
size_t delim = event.GetConnectionInfo()->remote_id.find('@');
if (delim != std::string::npos) {
HAL_Report(
HALUsageReporting::kResourceType_Dashboard,
HALUsageReporting::kDashboard_Unknown, 0,
event.GetConnectionInfo()->remote_id.substr(0, delim).c_str());
} else {
HAL_Report(HALUsageReporting::kResourceType_Dashboard,
HALUsageReporting::kDashboard_Unknown, 0,
event.GetConnectionInfo()->remote_id.c_str());
}
}
}
}
});
SmartDashboard::init();
if constexpr (!IsSimulation()) {

View File

@@ -10,6 +10,7 @@
#include <hal/DriverStation.h>
#include <hal/HALBase.h>
#include <hal/Main.h>
#include <networktables/NetworkTable.h>
#include <wpi/RuntimeCheck.h>
#include <wpi/condition_variable.h>
#include <wpi/mutex.h>
@@ -274,6 +275,8 @@ class RobotBase {
RobotBase& operator=(RobotBase&&) = default;
static std::thread::id m_threadId;
NT_Listener connListenerHandle;
bool m_dashboardDetected = false;
};
} // namespace frc

View File

@@ -14,6 +14,7 @@ import edu.wpi.first.math.MathShared;
import edu.wpi.first.math.MathSharedStore;
import edu.wpi.first.math.MathUsageId;
import edu.wpi.first.networktables.MultiSubscriber;
import edu.wpi.first.networktables.NetworkTableEvent;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.util.WPIUtilJNI;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
@@ -43,6 +44,10 @@ public abstract class RobotBase implements AutoCloseable {
private final MultiSubscriber m_suball;
private final int m_connListenerHandle;
private boolean m_dashboardDetected;
private static void setupCameraServerShared() {
CameraServerShared shared =
new CameraServerShared() {
@@ -158,6 +163,65 @@ public abstract class RobotBase implements AutoCloseable {
System.err.println("timed out while waiting for NT server to start");
}
m_connListenerHandle =
inst.addConnectionListener(
false,
event -> {
if (event.is(NetworkTableEvent.Kind.kConnected)) {
if (event.connInfo.remote_id.startsWith("glass")) {
HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Glass);
m_dashboardDetected = true;
} else if (event.connInfo.remote_id.startsWith("SmartDashboard")) {
HAL.report(
tResourceType.kResourceType_Dashboard, tInstances.kDashboard_SmartDashboard);
m_dashboardDetected = true;
} else if (event.connInfo.remote_id.startsWith("shuffleboard")) {
HAL.report(
tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Shuffleboard);
m_dashboardDetected = true;
} else if (event.connInfo.remote_id.startsWith("elastic")
|| event.connInfo.remote_id.startsWith("Elastic")) {
HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Elastic);
m_dashboardDetected = true;
} else if (event.connInfo.remote_id.startsWith("Dashboard")) {
HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_LabVIEW);
m_dashboardDetected = true;
} else if (event.connInfo.remote_id.startsWith("AdvantageScope")) {
HAL.report(
tResourceType.kResourceType_Dashboard, tInstances.kDashboard_AdvantageScope);
m_dashboardDetected = true;
} else if (event.connInfo.remote_id.startsWith("QFRCDashboard")) {
HAL.report(
tResourceType.kResourceType_Dashboard, tInstances.kDashboard_QFRCDashboard);
m_dashboardDetected = true;
} else if (event.connInfo.remote_id.startsWith("FRC Web Components")) {
HAL.report(
tResourceType.kResourceType_Dashboard,
tInstances.kDashboard_FRCWebComponents);
m_dashboardDetected = true;
} else {
// Only report unknown if there wasn't another dashboard already reported
// (unknown could also be another device)
if (!m_dashboardDetected) {
int delim = event.connInfo.remote_id.indexOf('@');
if (delim != -1) {
HAL.report(
tResourceType.kResourceType_Dashboard,
tInstances.kDashboard_Unknown,
0,
event.connInfo.remote_id.substring(0, delim));
} else {
HAL.report(
tResourceType.kResourceType_Dashboard,
tInstances.kDashboard_Unknown,
0,
event.connInfo.remote_id);
}
}
}
}
});
LiveWindow.setEnabled(false);
Shuffleboard.disableActuatorWidgets();
}
@@ -174,6 +238,7 @@ public abstract class RobotBase implements AutoCloseable {
@Override
public void close() {
m_suball.close();
NetworkTableInstance.getDefault().removeListener(m_connListenerHandle);
}
/**