mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpilib] Remove LiveWindow (#7733)
This will be replaced by a different mechanism, but removing it eases the initial implementation burden of a new Telemetry/Sendable framework.
This commit is contained in:
@@ -30,7 +30,7 @@ ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress)
|
||||
HAL_Report(HALUsageReporting::kResourceType_ADXL345,
|
||||
HALUsageReporting::kADXL345_I2C, 0);
|
||||
|
||||
wpi::SendableRegistry::AddLW(this, "ADXL345_I2C", port);
|
||||
wpi::SendableRegistry::Add(this, "ADXL345_I2C", port);
|
||||
}
|
||||
|
||||
I2C::Port ADXL345_I2C::GetI2CPort() const {
|
||||
|
||||
@@ -56,6 +56,6 @@ void AnalogAccelerometer::InitAccelerometer() {
|
||||
HAL_Report(HALUsageReporting::kResourceType_Accelerometer,
|
||||
m_analogInput->GetChannel() + 1);
|
||||
|
||||
wpi::SendableRegistry::AddLW(this, "Accelerometer",
|
||||
m_analogInput->GetChannel());
|
||||
wpi::SendableRegistry::Add(this, "Accelerometer",
|
||||
m_analogInput->GetChannel());
|
||||
}
|
||||
|
||||
@@ -67,8 +67,8 @@ void AnalogEncoder::Init(double fullRange, double expectedZero) {
|
||||
m_fullRange = fullRange;
|
||||
m_expectedZero = expectedZero;
|
||||
|
||||
wpi::SendableRegistry::AddLW(this, "Analog Encoder",
|
||||
m_analogInput->GetChannel());
|
||||
wpi::SendableRegistry::Add(this, "Analog Encoder",
|
||||
m_analogInput->GetChannel());
|
||||
}
|
||||
|
||||
double AnalogEncoder::Get() const {
|
||||
|
||||
@@ -35,7 +35,7 @@ AnalogInput::AnalogInput(int channel) {
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_AnalogChannel, channel + 1);
|
||||
|
||||
wpi::SendableRegistry::AddLW(this, "AnalogInput", channel);
|
||||
wpi::SendableRegistry::Add(this, "AnalogInput", channel);
|
||||
}
|
||||
|
||||
int AnalogInput::GetValue() const {
|
||||
|
||||
@@ -33,8 +33,8 @@ AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
|
||||
: m_analog_input(std::move(input)),
|
||||
m_fullRange(fullRange),
|
||||
m_offset(offset) {
|
||||
wpi::SendableRegistry::AddLW(this, "AnalogPotentiometer",
|
||||
m_analog_input->GetChannel());
|
||||
wpi::SendableRegistry::Add(this, "AnalogPotentiometer",
|
||||
m_analog_input->GetChannel());
|
||||
}
|
||||
|
||||
double AnalogPotentiometer::Get() const {
|
||||
|
||||
@@ -38,7 +38,7 @@ AnalogTrigger::AnalogTrigger(std::shared_ptr<AnalogInput> input)
|
||||
int index = GetIndex();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, index + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "AnalogTrigger", index);
|
||||
wpi::SendableRegistry::Add(this, "AnalogTrigger", index);
|
||||
}
|
||||
|
||||
AnalogTrigger::AnalogTrigger(DutyCycle& input)
|
||||
@@ -55,7 +55,7 @@ AnalogTrigger::AnalogTrigger(std::shared_ptr<DutyCycle> input)
|
||||
int index = GetIndex();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, index + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "AnalogTrigger", index);
|
||||
wpi::SendableRegistry::Add(this, "AnalogTrigger", index);
|
||||
}
|
||||
|
||||
void AnalogTrigger::SetLimitsVoltage(double lower, double upper) {
|
||||
|
||||
@@ -25,7 +25,7 @@ Compressor::Compressor(int module, PneumaticsModuleType moduleType)
|
||||
m_module->EnableCompressorDigital();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Compressor, module + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "Compressor", module);
|
||||
wpi::SendableRegistry::Add(this, "Compressor", module);
|
||||
}
|
||||
|
||||
Compressor::Compressor(PneumaticsModuleType moduleType)
|
||||
|
||||
@@ -27,7 +27,7 @@ Counter::Counter(Mode mode) {
|
||||
SetMaxPeriod(0.5_s);
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1, mode + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "Counter", m_index);
|
||||
wpi::SendableRegistry::Add(this, "Counter", m_index);
|
||||
}
|
||||
|
||||
Counter::Counter(int channel) : Counter(kTwoPulse) {
|
||||
|
||||
@@ -32,7 +32,7 @@ DigitalInput::DigitalInput(int channel) {
|
||||
FRC_CheckErrorStatus(status, "Channel {}", channel);
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_DigitalInput, channel + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "DigitalInput", channel);
|
||||
wpi::SendableRegistry::Add(this, "DigitalInput", channel);
|
||||
}
|
||||
|
||||
bool DigitalInput::Get() const {
|
||||
|
||||
@@ -33,7 +33,7 @@ DigitalOutput::DigitalOutput(int channel) {
|
||||
FRC_CheckErrorStatus(status, "Channel {}", channel);
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_DigitalOutput, channel + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "DigitalOutput", channel);
|
||||
wpi::SendableRegistry::Add(this, "DigitalOutput", channel);
|
||||
}
|
||||
|
||||
DigitalOutput::~DigitalOutput() {
|
||||
|
||||
@@ -55,8 +55,8 @@ DoubleSolenoid::DoubleSolenoid(int module, PneumaticsModuleType moduleType,
|
||||
HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel + 1,
|
||||
m_module->GetModuleNumber() + 1);
|
||||
|
||||
wpi::SendableRegistry::AddLW(this, "DoubleSolenoid",
|
||||
m_module->GetModuleNumber(), m_forwardChannel);
|
||||
wpi::SendableRegistry::Add(this, "DoubleSolenoid",
|
||||
m_module->GetModuleNumber(), m_forwardChannel);
|
||||
}
|
||||
|
||||
DoubleSolenoid::DoubleSolenoid(PneumaticsModuleType moduleType,
|
||||
@@ -129,7 +129,6 @@ bool DoubleSolenoid::IsRevSolenoidDisabled() const {
|
||||
void DoubleSolenoid::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Double Solenoid");
|
||||
builder.SetActuator(true);
|
||||
builder.SetSafeState([=, this] { Set(kOff); });
|
||||
builder.AddSmallStringProperty(
|
||||
"Value",
|
||||
[=, this](wpi::SmallVectorImpl<char>& buf) -> std::string_view {
|
||||
|
||||
@@ -34,7 +34,7 @@ void DutyCycle::InitDutyCycle() {
|
||||
&status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel());
|
||||
HAL_Report(HALUsageReporting::kResourceType_DutyCycle, m_channel + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "Duty Cycle", m_channel);
|
||||
wpi::SendableRegistry::Add(this, "Duty Cycle", m_channel);
|
||||
}
|
||||
|
||||
int DutyCycle::GetFPGAIndex() const {
|
||||
|
||||
@@ -74,8 +74,8 @@ void DutyCycleEncoder::Init(double fullRange, double expectedZero) {
|
||||
m_fullRange = fullRange;
|
||||
m_expectedZero = expectedZero;
|
||||
|
||||
wpi::SendableRegistry::AddLW(this, "DutyCycle Encoder",
|
||||
m_dutyCycle->GetSourceChannel());
|
||||
wpi::SendableRegistry::Add(this, "DutyCycle Encoder",
|
||||
m_dutyCycle->GetSourceChannel());
|
||||
}
|
||||
|
||||
double DutyCycleEncoder::Get() const {
|
||||
|
||||
@@ -234,7 +234,7 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) {
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex() + 1,
|
||||
encodingType);
|
||||
wpi::SendableRegistry::AddLW(this, "Encoder", m_aSource->GetChannel());
|
||||
wpi::SendableRegistry::Add(this, "Encoder", m_aSource->GetChannel());
|
||||
}
|
||||
|
||||
double Encoder::DecodingScaleFactor() const {
|
||||
|
||||
@@ -13,7 +13,6 @@
|
||||
|
||||
#include "frc/DSControlWord.h"
|
||||
#include "frc/Errors.h"
|
||||
#include "frc/livewindow/LiveWindow.h"
|
||||
#include "frc/smartdashboard/SmartDashboard.h"
|
||||
|
||||
using namespace frc;
|
||||
@@ -96,24 +95,6 @@ void IterativeRobotBase::SetNetworkTablesFlushEnabled(bool enabled) {
|
||||
m_ntFlushEnabled = enabled;
|
||||
}
|
||||
|
||||
void IterativeRobotBase::EnableLiveWindowInTest(bool testLW) {
|
||||
static bool hasReported;
|
||||
if (IsTestEnabled()) {
|
||||
throw FRC_MakeError(err::IncompatibleMode,
|
||||
"Can't configure test mode while in test mode!");
|
||||
}
|
||||
if (!hasReported && testLW) {
|
||||
HAL_Report(HALUsageReporting::kResourceType_SmartDashboard,
|
||||
HALUsageReporting::kSmartDashboard_LiveWindow);
|
||||
hasReported = true;
|
||||
}
|
||||
m_lwEnabledInTest = testLW;
|
||||
}
|
||||
|
||||
bool IterativeRobotBase::IsLiveWindowEnabledInTest() {
|
||||
return m_lwEnabledInTest;
|
||||
}
|
||||
|
||||
units::second_t IterativeRobotBase::GetPeriod() const {
|
||||
return m_period;
|
||||
}
|
||||
@@ -150,9 +131,6 @@ void IterativeRobotBase::LoopFunc() {
|
||||
} else if (m_lastMode == Mode::kTeleop) {
|
||||
TeleopExit();
|
||||
} else if (m_lastMode == Mode::kTest) {
|
||||
if (m_lwEnabledInTest) {
|
||||
LiveWindow::SetEnabled(false);
|
||||
}
|
||||
TestExit();
|
||||
}
|
||||
|
||||
@@ -167,9 +145,6 @@ void IterativeRobotBase::LoopFunc() {
|
||||
TeleopInit();
|
||||
m_watchdog.AddEpoch("TeleopInit()");
|
||||
} else if (mode == Mode::kTest) {
|
||||
if (m_lwEnabledInTest) {
|
||||
LiveWindow::SetEnabled(true);
|
||||
}
|
||||
TestInit();
|
||||
m_watchdog.AddEpoch("TestInit()");
|
||||
}
|
||||
@@ -201,8 +176,6 @@ void IterativeRobotBase::LoopFunc() {
|
||||
|
||||
SmartDashboard::UpdateValues();
|
||||
m_watchdog.AddEpoch("SmartDashboard::UpdateValues()");
|
||||
LiveWindow::UpdateValues();
|
||||
m_watchdog.AddEpoch("LiveWindow::UpdateValues()");
|
||||
|
||||
if constexpr (IsSimulation()) {
|
||||
HAL_SimPeriodicBefore();
|
||||
|
||||
@@ -40,7 +40,7 @@ PWM::PWM(int channel, bool registerSendable) {
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_PWM, channel + 1);
|
||||
if (registerSendable) {
|
||||
wpi::SendableRegistry::AddLW(this, "PWM", channel);
|
||||
wpi::SendableRegistry::Add(this, "PWM", channel);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -174,7 +174,6 @@ int PWM::GetChannel() const {
|
||||
void PWM::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("PWM");
|
||||
builder.SetActuator(true);
|
||||
builder.SetSafeState([=, this] { SetDisabled(); });
|
||||
builder.AddDoubleProperty(
|
||||
"Value", [=, this] { return GetPulseTime().value(); },
|
||||
[=, this](double value) { SetPulseTime(units::millisecond_t{value}); });
|
||||
|
||||
@@ -47,7 +47,7 @@ PowerDistribution::PowerDistribution() {
|
||||
HAL_Report(HALUsageReporting::kResourceType_PDP,
|
||||
HALUsageReporting::kPDP_REV);
|
||||
}
|
||||
wpi::SendableRegistry::AddLW(this, "PowerDistribution", m_module);
|
||||
wpi::SendableRegistry::Add(this, "PowerDistribution", m_module);
|
||||
}
|
||||
|
||||
PowerDistribution::PowerDistribution(int module, ModuleType moduleType) {
|
||||
@@ -68,7 +68,7 @@ PowerDistribution::PowerDistribution(int module, ModuleType moduleType) {
|
||||
HAL_Report(HALUsageReporting::kResourceType_PDP,
|
||||
HALUsageReporting::kPDP_REV);
|
||||
}
|
||||
wpi::SendableRegistry::AddLW(this, "PowerDistribution", m_module);
|
||||
wpi::SendableRegistry::Add(this, "PowerDistribution", m_module);
|
||||
}
|
||||
|
||||
int PowerDistribution::GetNumChannels() const {
|
||||
|
||||
@@ -31,7 +31,7 @@ SharpIR SharpIR::GP2Y0A51SK0F(int channel) {
|
||||
|
||||
SharpIR::SharpIR(int channel, double a, double b, double minCM, double maxCM)
|
||||
: m_sensor(channel), m_A(a), m_B(b), m_minCM(minCM), m_maxCM(maxCM) {
|
||||
wpi::SendableRegistry::AddLW(this, "SharpIR", channel);
|
||||
wpi::SendableRegistry::Add(this, "SharpIR", channel);
|
||||
|
||||
m_simDevice = hal::SimDevice("SharpIR", m_sensor.GetChannel());
|
||||
if (m_simDevice) {
|
||||
|
||||
@@ -30,8 +30,8 @@ Solenoid::Solenoid(int module, PneumaticsModuleType moduleType, int channel)
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_channel + 1,
|
||||
m_module->GetModuleNumber() + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "Solenoid", m_module->GetModuleNumber(),
|
||||
m_channel);
|
||||
wpi::SendableRegistry::Add(this, "Solenoid", m_module->GetModuleNumber(),
|
||||
m_channel);
|
||||
}
|
||||
|
||||
Solenoid::Solenoid(PneumaticsModuleType moduleType, int channel)
|
||||
@@ -77,7 +77,6 @@ void Solenoid::StartPulse() {
|
||||
void Solenoid::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Solenoid");
|
||||
builder.SetActuator(true);
|
||||
builder.SetSafeState([=, this] { Set(false); });
|
||||
builder.AddBooleanProperty(
|
||||
"Value", [=, this] { return Get(); },
|
||||
[=, this](bool value) { Set(value); });
|
||||
|
||||
@@ -183,7 +183,7 @@ void Ultrasonic::Initialize() {
|
||||
static int instances = 0;
|
||||
instances++;
|
||||
HAL_Report(HALUsageReporting::kResourceType_Ultrasonic, instances);
|
||||
wpi::SendableRegistry::AddLW(this, "Ultrasonic", m_echoChannel->GetChannel());
|
||||
wpi::SendableRegistry::Add(this, "Ultrasonic", m_echoChannel->GetChannel());
|
||||
}
|
||||
|
||||
void Ultrasonic::UltrasonicChecker() {
|
||||
|
||||
@@ -60,7 +60,7 @@ ExternalDirectionCounter::ExternalDirectionCounter(
|
||||
Reset();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "External Direction Counter", m_index);
|
||||
wpi::SendableRegistry::Add(this, "External Direction Counter", m_index);
|
||||
}
|
||||
|
||||
int ExternalDirectionCounter::GetCount() const {
|
||||
|
||||
@@ -34,7 +34,7 @@ Tachometer::Tachometer(std::shared_ptr<DigitalSource> source) {
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "Tachometer", m_index);
|
||||
wpi::SendableRegistry::Add(this, "Tachometer", m_index);
|
||||
}
|
||||
|
||||
units::hertz_t Tachometer::GetFrequency() const {
|
||||
|
||||
@@ -54,7 +54,7 @@ UpDownCounter::UpDownCounter(std::shared_ptr<DigitalSource> upSource,
|
||||
Reset();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "UpDown Counter", m_index);
|
||||
wpi::SendableRegistry::Add(this, "UpDown Counter", m_index);
|
||||
}
|
||||
|
||||
int UpDownCounter::GetCount() const {
|
||||
|
||||
@@ -35,7 +35,7 @@ DifferentialDrive::DifferentialDrive(std::function<void(double)> leftMotor,
|
||||
: m_leftMotor{std::move(leftMotor)}, m_rightMotor{std::move(rightMotor)} {
|
||||
static int instances = 0;
|
||||
++instances;
|
||||
wpi::SendableRegistry::AddLW(this, "DifferentialDrive", instances);
|
||||
wpi::SendableRegistry::Add(this, "DifferentialDrive", instances);
|
||||
}
|
||||
|
||||
void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation,
|
||||
@@ -194,7 +194,6 @@ std::string DifferentialDrive::GetDescription() const {
|
||||
void DifferentialDrive::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("DifferentialDrive");
|
||||
builder.SetActuator(true);
|
||||
builder.SetSafeState([=, this] { StopMotor(); });
|
||||
builder.AddDoubleProperty(
|
||||
"Left Motor Speed", [&] { return m_leftOutput; }, m_leftMotor);
|
||||
builder.AddDoubleProperty(
|
||||
|
||||
@@ -46,7 +46,7 @@ MecanumDrive::MecanumDrive(std::function<void(double)> frontLeftMotor,
|
||||
m_rearRightMotor{std::move(rearRightMotor)} {
|
||||
static int instances = 0;
|
||||
++instances;
|
||||
wpi::SendableRegistry::AddLW(this, "MecanumDrive", instances);
|
||||
wpi::SendableRegistry::Add(this, "MecanumDrive", instances);
|
||||
}
|
||||
|
||||
void MecanumDrive::DriveCartesian(double xSpeed, double ySpeed,
|
||||
@@ -133,7 +133,6 @@ std::string MecanumDrive::GetDescription() const {
|
||||
void MecanumDrive::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("MecanumDrive");
|
||||
builder.SetActuator(true);
|
||||
builder.SetSafeState([=, this] { StopMotor(); });
|
||||
builder.AddDoubleProperty(
|
||||
"Front Left Motor Speed", [&] { return m_frontLeftOutput; },
|
||||
m_frontLeftMotor);
|
||||
|
||||
@@ -1,230 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "frc/livewindow/LiveWindow.h"
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <networktables/BooleanTopic.h>
|
||||
#include <networktables/NetworkTable.h>
|
||||
#include <networktables/NetworkTableInstance.h>
|
||||
#include <networktables/StringTopic.h>
|
||||
#include <wpi/json.h>
|
||||
#include <wpi/mutex.h>
|
||||
#include <wpi/sendable/Sendable.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
|
||||
#include "frc/smartdashboard/SendableBuilderImpl.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
static constexpr std::string_view kSmartDashboardType = "LW Subsystem";
|
||||
|
||||
namespace {
|
||||
struct Component {
|
||||
bool firstTime = true;
|
||||
bool telemetryEnabled = false;
|
||||
nt::StringPublisher namePub;
|
||||
nt::StringPublisher typePub;
|
||||
};
|
||||
|
||||
struct Instance {
|
||||
Instance() {
|
||||
wpi::SendableRegistry::SetLiveWindowBuilderFactory(
|
||||
[] { return std::make_unique<SendableBuilderImpl>(); });
|
||||
enabledPub.Set(false);
|
||||
}
|
||||
|
||||
wpi::mutex mutex;
|
||||
|
||||
int dataHandle = wpi::SendableRegistry::GetDataHandle();
|
||||
|
||||
std::shared_ptr<nt::NetworkTable> liveWindowTable =
|
||||
nt::NetworkTableInstance::GetDefault().GetTable("LiveWindow");
|
||||
std::shared_ptr<nt::NetworkTable> statusTable =
|
||||
liveWindowTable->GetSubTable(".status");
|
||||
nt::BooleanPublisher enabledPub =
|
||||
statusTable->GetBooleanTopic("LW Enabled").Publish();
|
||||
|
||||
bool startLiveWindow = false;
|
||||
bool liveWindowEnabled = false;
|
||||
bool telemetryEnabled = false;
|
||||
|
||||
std::function<void()> enabled;
|
||||
std::function<void()> disabled;
|
||||
|
||||
std::shared_ptr<Component> GetOrAdd(wpi::Sendable* sendable);
|
||||
};
|
||||
} // namespace
|
||||
|
||||
static std::unique_ptr<Instance>& GetInstanceHolder() {
|
||||
static std::unique_ptr<Instance> instance = std::make_unique<Instance>();
|
||||
return instance;
|
||||
}
|
||||
|
||||
static Instance& GetInstance() {
|
||||
return *GetInstanceHolder();
|
||||
}
|
||||
|
||||
#ifndef __FRC_ROBORIO__
|
||||
namespace frc::impl {
|
||||
void ResetLiveWindow() {
|
||||
std::make_unique<Instance>().swap(GetInstanceHolder());
|
||||
}
|
||||
} // namespace frc::impl
|
||||
#endif
|
||||
|
||||
std::shared_ptr<Component> Instance::GetOrAdd(wpi::Sendable* sendable) {
|
||||
auto data = std::static_pointer_cast<Component>(
|
||||
wpi::SendableRegistry::GetData(sendable, dataHandle));
|
||||
if (!data) {
|
||||
data = std::make_shared<Component>();
|
||||
wpi::SendableRegistry::SetData(sendable, dataHandle, data);
|
||||
}
|
||||
return data;
|
||||
}
|
||||
|
||||
void LiveWindow::SetEnabledCallback(std::function<void()> func) {
|
||||
::GetInstance().enabled = func;
|
||||
}
|
||||
|
||||
void LiveWindow::SetDisabledCallback(std::function<void()> func) {
|
||||
::GetInstance().disabled = func;
|
||||
}
|
||||
|
||||
void LiveWindow::EnableTelemetry(wpi::Sendable* sendable) {
|
||||
auto& inst = ::GetInstance();
|
||||
std::scoped_lock lock(inst.mutex);
|
||||
// Re-enable global setting in case DisableAllTelemetry() was called.
|
||||
inst.telemetryEnabled = true;
|
||||
inst.GetOrAdd(sendable)->telemetryEnabled = true;
|
||||
}
|
||||
|
||||
void LiveWindow::DisableTelemetry(wpi::Sendable* sendable) {
|
||||
auto& inst = ::GetInstance();
|
||||
std::scoped_lock lock(inst.mutex);
|
||||
inst.GetOrAdd(sendable)->telemetryEnabled = false;
|
||||
}
|
||||
|
||||
void LiveWindow::DisableAllTelemetry() {
|
||||
auto& inst = ::GetInstance();
|
||||
std::scoped_lock lock(inst.mutex);
|
||||
inst.telemetryEnabled = false;
|
||||
wpi::SendableRegistry::ForeachLiveWindow(inst.dataHandle, [&](auto& cbdata) {
|
||||
if (!cbdata.data) {
|
||||
cbdata.data = std::make_shared<Component>();
|
||||
}
|
||||
std::static_pointer_cast<Component>(cbdata.data)->telemetryEnabled = false;
|
||||
});
|
||||
}
|
||||
|
||||
void LiveWindow::EnableAllTelemetry() {
|
||||
auto& inst = ::GetInstance();
|
||||
std::scoped_lock lock(inst.mutex);
|
||||
inst.telemetryEnabled = true;
|
||||
wpi::SendableRegistry::ForeachLiveWindow(inst.dataHandle, [&](auto& cbdata) {
|
||||
if (!cbdata.data) {
|
||||
cbdata.data = std::make_shared<Component>();
|
||||
}
|
||||
std::static_pointer_cast<Component>(cbdata.data)->telemetryEnabled = true;
|
||||
});
|
||||
}
|
||||
|
||||
bool LiveWindow::IsEnabled() {
|
||||
auto& inst = ::GetInstance();
|
||||
std::scoped_lock lock(inst.mutex);
|
||||
return inst.liveWindowEnabled;
|
||||
}
|
||||
|
||||
void LiveWindow::SetEnabled(bool enabled) {
|
||||
auto& inst = ::GetInstance();
|
||||
std::scoped_lock lock(inst.mutex);
|
||||
if (inst.liveWindowEnabled == enabled) {
|
||||
return;
|
||||
}
|
||||
inst.startLiveWindow = enabled;
|
||||
inst.liveWindowEnabled = enabled;
|
||||
// Force table generation now to make sure everything is defined
|
||||
UpdateValuesUnsafe();
|
||||
if (enabled) {
|
||||
if (inst.enabled) {
|
||||
inst.enabled();
|
||||
}
|
||||
} else {
|
||||
wpi::SendableRegistry::ForeachLiveWindow(
|
||||
inst.dataHandle, [&](auto& cbdata) {
|
||||
static_cast<SendableBuilderImpl&>(cbdata.builder)
|
||||
.StopLiveWindowMode();
|
||||
});
|
||||
if (inst.disabled) {
|
||||
inst.disabled();
|
||||
}
|
||||
}
|
||||
inst.enabledPub.Set(enabled);
|
||||
}
|
||||
|
||||
void LiveWindow::UpdateValues() {
|
||||
auto& inst = ::GetInstance();
|
||||
std::scoped_lock lock(inst.mutex);
|
||||
UpdateValuesUnsafe();
|
||||
}
|
||||
|
||||
void LiveWindow::UpdateValuesUnsafe() {
|
||||
auto& inst = ::GetInstance();
|
||||
// Only do this if either LiveWindow mode or telemetry is enabled.
|
||||
if (!inst.liveWindowEnabled && !inst.telemetryEnabled) {
|
||||
return;
|
||||
}
|
||||
|
||||
wpi::SendableRegistry::ForeachLiveWindow(inst.dataHandle, [&](auto& cbdata) {
|
||||
if (!cbdata.sendable || cbdata.parent) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (!cbdata.data) {
|
||||
cbdata.data = std::make_shared<Component>();
|
||||
}
|
||||
|
||||
auto& comp = *std::static_pointer_cast<Component>(cbdata.data);
|
||||
|
||||
if (!inst.liveWindowEnabled && !comp.telemetryEnabled) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (comp.firstTime) {
|
||||
// By holding off creating the NetworkTable entries, it allows the
|
||||
// components to be redefined. This allows default sensor and actuator
|
||||
// values to be created that are replaced with the custom names from
|
||||
// users calling setName.
|
||||
if (cbdata.name.empty()) {
|
||||
return;
|
||||
}
|
||||
auto ssTable = inst.liveWindowTable->GetSubTable(cbdata.subsystem);
|
||||
std::shared_ptr<nt::NetworkTable> table;
|
||||
// Treat name==subsystem as top level of subsystem
|
||||
if (cbdata.name == cbdata.subsystem) {
|
||||
table = ssTable;
|
||||
} else {
|
||||
table = ssTable->GetSubTable(cbdata.name);
|
||||
}
|
||||
comp.namePub = nt::StringTopic{table->GetTopic(".name")}.Publish();
|
||||
comp.namePub.Set(cbdata.name);
|
||||
static_cast<SendableBuilderImpl&>(cbdata.builder).SetTable(table);
|
||||
cbdata.sendable->InitSendable(cbdata.builder);
|
||||
comp.typePub = nt::StringTopic{ssTable->GetTopic(".type")}.PublishEx(
|
||||
nt::StringTopic::kTypeString,
|
||||
{{"SmartDashboard", kSmartDashboardType}});
|
||||
comp.typePub.Set(kSmartDashboardType);
|
||||
|
||||
comp.firstTime = false;
|
||||
}
|
||||
|
||||
if (inst.startLiveWindow) {
|
||||
static_cast<SendableBuilderImpl&>(cbdata.builder).StartLiveWindowMode();
|
||||
}
|
||||
cbdata.builder.Update();
|
||||
});
|
||||
|
||||
inst.startLiveWindow = false;
|
||||
}
|
||||
@@ -74,7 +74,6 @@ void MotorControllerGroup::StopMotor() {
|
||||
void MotorControllerGroup::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Motor Controller");
|
||||
builder.SetActuator(true);
|
||||
builder.SetSafeState([=, this] { StopMotor(); });
|
||||
builder.AddDoubleProperty(
|
||||
"Value", [=, this] { return Get(); },
|
||||
[=, this](double value) { Set(value); });
|
||||
|
||||
@@ -27,7 +27,7 @@ NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
|
||||
m_dio.EnablePWM(0.5);
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_NidecBrushless, pwmChannel + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "Nidec Brushless", pwmChannel);
|
||||
wpi::SendableRegistry::Add(this, "Nidec Brushless", pwmChannel);
|
||||
}
|
||||
|
||||
WPI_UNIGNORE_DEPRECATED
|
||||
@@ -79,7 +79,6 @@ int NidecBrushless::GetChannel() const {
|
||||
void NidecBrushless::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Nidec Brushless");
|
||||
builder.SetActuator(true);
|
||||
builder.SetSafeState([=, this] { StopMotor(); });
|
||||
builder.AddDoubleProperty(
|
||||
"Value", [=, this] { return Get(); },
|
||||
[=, this](double value) { Set(value); });
|
||||
|
||||
@@ -94,7 +94,7 @@ WPI_IGNORE_DEPRECATED
|
||||
|
||||
PWMMotorController::PWMMotorController(std::string_view name, int channel)
|
||||
: m_pwm(channel, false) {
|
||||
wpi::SendableRegistry::AddLW(this, name, channel);
|
||||
wpi::SendableRegistry::Add(this, name, channel);
|
||||
}
|
||||
|
||||
WPI_UNIGNORE_DEPRECATED
|
||||
@@ -102,7 +102,6 @@ WPI_UNIGNORE_DEPRECATED
|
||||
void PWMMotorController::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Motor Controller");
|
||||
builder.SetActuator(true);
|
||||
builder.SetSafeState([=, this] { Disable(); });
|
||||
builder.AddDoubleProperty(
|
||||
"Value", [=, this] { return Get(); },
|
||||
[=, this](double value) { Set(value); });
|
||||
|
||||
@@ -77,20 +77,6 @@ void SendableBuilderImpl::StopListeners() {
|
||||
}
|
||||
}
|
||||
|
||||
void SendableBuilderImpl::StartLiveWindowMode() {
|
||||
if (m_safeState) {
|
||||
m_safeState();
|
||||
}
|
||||
StartListeners();
|
||||
}
|
||||
|
||||
void SendableBuilderImpl::StopLiveWindowMode() {
|
||||
StopListeners();
|
||||
if (m_safeState) {
|
||||
m_safeState();
|
||||
}
|
||||
}
|
||||
|
||||
void SendableBuilderImpl::ClearProperties() {
|
||||
m_properties.clear();
|
||||
}
|
||||
@@ -111,10 +97,6 @@ void SendableBuilderImpl::SetActuator(bool value) {
|
||||
m_actuator = value;
|
||||
}
|
||||
|
||||
void SendableBuilderImpl::SetSafeState(std::function<void()> func) {
|
||||
m_safeState = func;
|
||||
}
|
||||
|
||||
void SendableBuilderImpl::SetUpdateTable(wpi::unique_function<void()> func) {
|
||||
m_updateTables.emplace_back(std::move(func));
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user