Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add usage reporting for dashboards as instances #7294

Merged
merged 12 commits into from
Nov 18, 2024
9 changes: 9 additions & 0 deletions hal/src/generate/Instances.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
18 changes: 18 additions & 0 deletions hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

9 changes: 9 additions & 0 deletions hal/src/generated/main/native/include/hal/UsageReporting.h

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

62 changes: 62 additions & 0 deletions wpilibc/src/main/native/cppcs/RobotBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down Expand Up @@ -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()) {
Expand Down
3 changes: 3 additions & 0 deletions wpilibc/src/main/native/include/frc/RobotBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down Expand Up @@ -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
65 changes: 65 additions & 0 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
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;
Expand Down Expand Up @@ -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() {
Expand Down Expand Up @@ -158,6 +163,65 @@ protected RobotBase() {
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();
}
Expand All @@ -174,6 +238,7 @@ public static long getMainThreadId() {
@Override
public void close() {
m_suball.close();
NetworkTableInstance.getDefault().removeListener(m_connListenerHandle);
}

/**
Expand Down
Loading