diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LogBackedSendableBuilder.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LogBackedSendableBuilder.java index 5de5756ff4f..4b93a88ee55 100644 --- a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LogBackedSendableBuilder.java +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LogBackedSendableBuilder.java @@ -43,11 +43,6 @@ public void setActuator(boolean value) { // ignore } - @Override - public void setSafeState(Runnable func) { - // ignore - } - @Override public void addBooleanProperty(String key, BooleanSupplier getter, BooleanConsumer setter) { m_updates.add(() -> m_backend.log(key, getter.getAsBoolean())); diff --git a/gradle.properties b/gradle.properties index ac38aaaad1c..1e28aedd1be 100644 --- a/gradle.properties +++ b/gradle.properties @@ -1,2 +1,2 @@ -org.gradle.jvmargs=-Xmx2g +org.gradle.jvmargs=-Xmx4g org.ysb33r.gradle.doxygen.download.url=https://frcmaven.wpi.edu/artifactory/generic-release-mirror/doxygen diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java index 15babf85bbf..34319caa079 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java @@ -18,7 +18,6 @@ import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.Watchdog; import edu.wpi.first.wpilibj.event.EventLoop; -import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior; import java.io.PrintWriter; import java.io.StringWriter; @@ -101,13 +100,7 @@ public static synchronized CommandScheduler getInstance() { CommandScheduler() { HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand2_Scheduler); - SendableRegistry.addLW(this, "Scheduler"); - LiveWindow.setEnabledListener( - () -> { - disable(); - cancelAll(); - }); - LiveWindow.setDisabledListener(this::enable); + SendableRegistry.add(this, "Scheduler"); } /** @@ -123,8 +116,6 @@ public void setPeriod(double period) { @Override public void close() { SendableRegistry.remove(this); - LiveWindow.setEnabledListener(null); - LiveWindow.setDisabledListener(null); } /** diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java index 3a024e5f665..0ab58cd4fbe 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java @@ -20,7 +20,7 @@ public abstract class SubsystemBase implements Subsystem, Sendable { public SubsystemBase() { String name = this.getClass().getSimpleName(); name = name.substring(name.lastIndexOf('.') + 1); - SendableRegistry.addLW(this, name, name); + SendableRegistry.add(this, name, name); CommandScheduler.getInstance().registerSubsystem(this); } @@ -31,7 +31,7 @@ public SubsystemBase() { */ @SuppressWarnings("this-escape") public SubsystemBase(String name) { - SendableRegistry.addLW(this, name, name); + SendableRegistry.add(this, name, name); CommandScheduler.getInstance().registerSubsystem(this); } @@ -79,7 +79,7 @@ public void setSubsystem(String subsystem) { * @param child sendable */ public void addChild(String name, Sendable child) { - SendableRegistry.addLW(child, getSubsystem(), name); + SendableRegistry.add(child, getSubsystem(), name); } @Override diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp index 369e14367bc..b077de5e538 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp @@ -13,7 +13,6 @@ #include #include #include -#include #include #include #include @@ -72,19 +71,11 @@ CommandScheduler::CommandScheduler() }) { HAL_Report(HALUsageReporting::kResourceType_Command, HALUsageReporting::kCommand2_Scheduler); - wpi::SendableRegistry::AddLW(this, "Scheduler"); - frc::LiveWindow::SetEnabledCallback([this] { - this->Disable(); - this->CancelAll(); - }); - frc::LiveWindow::SetDisabledCallback([this] { this->Enable(); }); + wpi::SendableRegistry::Add(this, "Scheduler"); } CommandScheduler::~CommandScheduler() { wpi::SendableRegistry::Remove(this); - frc::LiveWindow::SetEnabledCallback(nullptr); - frc::LiveWindow::SetDisabledCallback(nullptr); - std::unique_ptr().swap(m_impl); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/SubsystemBase.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/SubsystemBase.cpp index e0638263642..d66b6bfc818 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/SubsystemBase.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/SubsystemBase.cpp @@ -15,12 +15,12 @@ using namespace frc2; SubsystemBase::SubsystemBase() { - wpi::SendableRegistry::AddLW(this, GetTypeName(*this)); + wpi::SendableRegistry::Add(this, GetTypeName(*this)); CommandScheduler::GetInstance().RegisterSubsystem({this}); } SubsystemBase::SubsystemBase(std::string_view name) { - wpi::SendableRegistry::AddLW(this, name); + wpi::SendableRegistry::Add(this, name); CommandScheduler::GetInstance().RegisterSubsystem({this}); } @@ -71,5 +71,5 @@ void SubsystemBase::SetSubsystem(std::string_view name) { } void SubsystemBase::AddChild(std::string name, wpi::Sendable* child) { - wpi::SendableRegistry::AddLW(child, GetSubsystem(), name); + wpi::SendableRegistry::Add(child, GetSubsystem(), name); } diff --git a/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp b/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp index a23846d8291..1fdf71ed373 100644 --- a/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp +++ b/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp @@ -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 { diff --git a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp index ca8af7d5d9d..70d91fcef94 100644 --- a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp +++ b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp @@ -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()); } diff --git a/wpilibc/src/main/native/cpp/AnalogEncoder.cpp b/wpilibc/src/main/native/cpp/AnalogEncoder.cpp index 13a788788cb..c251ebcf5eb 100644 --- a/wpilibc/src/main/native/cpp/AnalogEncoder.cpp +++ b/wpilibc/src/main/native/cpp/AnalogEncoder.cpp @@ -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 { diff --git a/wpilibc/src/main/native/cpp/AnalogInput.cpp b/wpilibc/src/main/native/cpp/AnalogInput.cpp index 188ddb74994..84f168e18e3 100644 --- a/wpilibc/src/main/native/cpp/AnalogInput.cpp +++ b/wpilibc/src/main/native/cpp/AnalogInput.cpp @@ -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 { diff --git a/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp b/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp index 31432e9681c..2855464bd64 100644 --- a/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp +++ b/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp @@ -33,8 +33,8 @@ AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr 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 { diff --git a/wpilibc/src/main/native/cpp/AnalogTrigger.cpp b/wpilibc/src/main/native/cpp/AnalogTrigger.cpp index 6759b61dde6..ca441103a04 100644 --- a/wpilibc/src/main/native/cpp/AnalogTrigger.cpp +++ b/wpilibc/src/main/native/cpp/AnalogTrigger.cpp @@ -38,7 +38,7 @@ AnalogTrigger::AnalogTrigger(std::shared_ptr 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 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) { diff --git a/wpilibc/src/main/native/cpp/Compressor.cpp b/wpilibc/src/main/native/cpp/Compressor.cpp index 1306561fcba..bb9a62fbd18 100644 --- a/wpilibc/src/main/native/cpp/Compressor.cpp +++ b/wpilibc/src/main/native/cpp/Compressor.cpp @@ -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) diff --git a/wpilibc/src/main/native/cpp/Counter.cpp b/wpilibc/src/main/native/cpp/Counter.cpp index 32523c245a2..2021443f5ad 100644 --- a/wpilibc/src/main/native/cpp/Counter.cpp +++ b/wpilibc/src/main/native/cpp/Counter.cpp @@ -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) { diff --git a/wpilibc/src/main/native/cpp/DigitalInput.cpp b/wpilibc/src/main/native/cpp/DigitalInput.cpp index f6c2d8b03c6..4c1474f0d96 100644 --- a/wpilibc/src/main/native/cpp/DigitalInput.cpp +++ b/wpilibc/src/main/native/cpp/DigitalInput.cpp @@ -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 { diff --git a/wpilibc/src/main/native/cpp/DigitalOutput.cpp b/wpilibc/src/main/native/cpp/DigitalOutput.cpp index ee54bb4294d..3a2ec092cae 100644 --- a/wpilibc/src/main/native/cpp/DigitalOutput.cpp +++ b/wpilibc/src/main/native/cpp/DigitalOutput.cpp @@ -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() { diff --git a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp index c111622545c..f87d3ebeb7c 100644 --- a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp +++ b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp @@ -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& buf) -> std::string_view { diff --git a/wpilibc/src/main/native/cpp/DutyCycle.cpp b/wpilibc/src/main/native/cpp/DutyCycle.cpp index 6045e3cd71f..1a5c23dddc8 100644 --- a/wpilibc/src/main/native/cpp/DutyCycle.cpp +++ b/wpilibc/src/main/native/cpp/DutyCycle.cpp @@ -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 { diff --git a/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp b/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp index e94c6a331be..5f1eabd60c1 100644 --- a/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp +++ b/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp @@ -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 { diff --git a/wpilibc/src/main/native/cpp/Encoder.cpp b/wpilibc/src/main/native/cpp/Encoder.cpp index b7eda548fea..522f4801faf 100644 --- a/wpilibc/src/main/native/cpp/Encoder.cpp +++ b/wpilibc/src/main/native/cpp/Encoder.cpp @@ -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 { diff --git a/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp b/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp index 2a97988b19a..fc105a21193 100644 --- a/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp +++ b/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp @@ -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(); diff --git a/wpilibc/src/main/native/cpp/PWM.cpp b/wpilibc/src/main/native/cpp/PWM.cpp index f623ba40ff9..bf8d1b87cfc 100644 --- a/wpilibc/src/main/native/cpp/PWM.cpp +++ b/wpilibc/src/main/native/cpp/PWM.cpp @@ -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}); }); diff --git a/wpilibc/src/main/native/cpp/PowerDistribution.cpp b/wpilibc/src/main/native/cpp/PowerDistribution.cpp index af0d308e656..a034723cbba 100644 --- a/wpilibc/src/main/native/cpp/PowerDistribution.cpp +++ b/wpilibc/src/main/native/cpp/PowerDistribution.cpp @@ -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 { diff --git a/wpilibc/src/main/native/cpp/SharpIR.cpp b/wpilibc/src/main/native/cpp/SharpIR.cpp index 67e00f6a67e..084ad3b3cf5 100644 --- a/wpilibc/src/main/native/cpp/SharpIR.cpp +++ b/wpilibc/src/main/native/cpp/SharpIR.cpp @@ -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) { diff --git a/wpilibc/src/main/native/cpp/Solenoid.cpp b/wpilibc/src/main/native/cpp/Solenoid.cpp index 819f79a8d71..5bccc8a762b 100644 --- a/wpilibc/src/main/native/cpp/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/Solenoid.cpp @@ -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); }); diff --git a/wpilibc/src/main/native/cpp/Ultrasonic.cpp b/wpilibc/src/main/native/cpp/Ultrasonic.cpp index 640a56c4f41..3b50b913401 100644 --- a/wpilibc/src/main/native/cpp/Ultrasonic.cpp +++ b/wpilibc/src/main/native/cpp/Ultrasonic.cpp @@ -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() { diff --git a/wpilibc/src/main/native/cpp/counter/ExternalDirectionCounter.cpp b/wpilibc/src/main/native/cpp/counter/ExternalDirectionCounter.cpp index d518a2f0fc5..3b7d8a8aa4d 100644 --- a/wpilibc/src/main/native/cpp/counter/ExternalDirectionCounter.cpp +++ b/wpilibc/src/main/native/cpp/counter/ExternalDirectionCounter.cpp @@ -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 { diff --git a/wpilibc/src/main/native/cpp/counter/Tachometer.cpp b/wpilibc/src/main/native/cpp/counter/Tachometer.cpp index b5a32b807ed..aae658e8c46 100644 --- a/wpilibc/src/main/native/cpp/counter/Tachometer.cpp +++ b/wpilibc/src/main/native/cpp/counter/Tachometer.cpp @@ -34,7 +34,7 @@ Tachometer::Tachometer(std::shared_ptr 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 { diff --git a/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp b/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp index 7da57924777..2cda45a0da8 100644 --- a/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp +++ b/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp @@ -54,7 +54,7 @@ UpDownCounter::UpDownCounter(std::shared_ptr 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 { diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index 85232193a41..abd2df149c0 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -35,7 +35,7 @@ DifferentialDrive::DifferentialDrive(std::function 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( diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index d40d02c6343..0cafcb57c88 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -46,7 +46,7 @@ MecanumDrive::MecanumDrive(std::function 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); diff --git a/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp b/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp deleted file mode 100644 index 04f66c723e5..00000000000 --- a/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp +++ /dev/null @@ -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 - -#include -#include -#include -#include -#include -#include -#include -#include - -#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(); }); - enabledPub.Set(false); - } - - wpi::mutex mutex; - - int dataHandle = wpi::SendableRegistry::GetDataHandle(); - - std::shared_ptr liveWindowTable = - nt::NetworkTableInstance::GetDefault().GetTable("LiveWindow"); - std::shared_ptr statusTable = - liveWindowTable->GetSubTable(".status"); - nt::BooleanPublisher enabledPub = - statusTable->GetBooleanTopic("LW Enabled").Publish(); - - bool startLiveWindow = false; - bool liveWindowEnabled = false; - bool telemetryEnabled = false; - - std::function enabled; - std::function disabled; - - std::shared_ptr GetOrAdd(wpi::Sendable* sendable); -}; -} // namespace - -static std::unique_ptr& GetInstanceHolder() { - static std::unique_ptr instance = std::make_unique(); - return instance; -} - -static Instance& GetInstance() { - return *GetInstanceHolder(); -} - -#ifndef __FRC_ROBORIO__ -namespace frc::impl { -void ResetLiveWindow() { - std::make_unique().swap(GetInstanceHolder()); -} -} // namespace frc::impl -#endif - -std::shared_ptr Instance::GetOrAdd(wpi::Sendable* sendable) { - auto data = std::static_pointer_cast( - wpi::SendableRegistry::GetData(sendable, dataHandle)); - if (!data) { - data = std::make_shared(); - wpi::SendableRegistry::SetData(sendable, dataHandle, data); - } - return data; -} - -void LiveWindow::SetEnabledCallback(std::function func) { - ::GetInstance().enabled = func; -} - -void LiveWindow::SetDisabledCallback(std::function 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(); - } - std::static_pointer_cast(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(); - } - std::static_pointer_cast(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(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(); - } - - auto& comp = *std::static_pointer_cast(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 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(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(cbdata.builder).StartLiveWindowMode(); - } - cbdata.builder.Update(); - }); - - inst.startLiveWindow = false; -} diff --git a/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp b/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp index c5a0e0316f4..5c0266b054b 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp @@ -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); }); diff --git a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp index 5acf3c818d0..0342a01cea2 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp @@ -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); }); diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp index 28ef00fbef5..f33a54d79cf 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp @@ -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); }); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp index 0098eae7367..ff42ea5cc85 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp @@ -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 func) { - m_safeState = func; -} - void SendableBuilderImpl::SetUpdateTable(wpi::unique_function func) { m_updateTables.emplace_back(std::move(func)); } diff --git a/wpilibc/src/main/native/cppcs/RobotBase.cpp b/wpilibc/src/main/native/cppcs/RobotBase.cpp index 58f1ec81b5c..c7113dc330a 100644 --- a/wpilibc/src/main/native/cppcs/RobotBase.cpp +++ b/wpilibc/src/main/native/cppcs/RobotBase.cpp @@ -26,7 +26,6 @@ #include "frc/DriverStation.h" #include "frc/Errors.h" #include "frc/Notifier.h" -#include "frc/livewindow/LiveWindow.h" #include "frc/smartdashboard/SmartDashboard.h" static_assert(frc::RuntimeType::kRoboRIO == @@ -333,7 +332,4 @@ RobotBase::RobotBase() { // Call DriverStation::RefreshData() to kick things off DriverStation::RefreshData(); - - // First and one-time initialization - LiveWindow::SetEnabled(false); } diff --git a/wpilibc/src/main/native/include/frc/IterativeRobotBase.h b/wpilibc/src/main/native/include/frc/IterativeRobotBase.h index 79f7fb2cab0..70cc2c34f48 100644 --- a/wpilibc/src/main/native/include/frc/IterativeRobotBase.h +++ b/wpilibc/src/main/native/include/frc/IterativeRobotBase.h @@ -212,19 +212,6 @@ class IterativeRobotBase : public RobotBase { [[deprecated("Deprecated without replacement.")]] void SetNetworkTablesFlushEnabled(bool enabled); - /** - * Sets whether LiveWindow operation is enabled during test mode. - * - * @param testLW True to enable, false to disable. Defaults to false. - * @throws if called in test mode. - */ - void EnableLiveWindowInTest(bool testLW); - - /** - * Whether LiveWindow operation is enabled during test mode. - */ - bool IsLiveWindowEnabledInTest(); - /** * Gets time period between calls to Periodic() functions. */ @@ -260,7 +247,6 @@ class IterativeRobotBase : public RobotBase { units::second_t m_period; Watchdog m_watchdog; bool m_ntFlushEnabled = true; - bool m_lwEnabledInTest = false; bool m_calledDsConnected = false; void PrintLoopOverrunMessage(); diff --git a/wpilibc/src/main/native/include/frc/PWM.h b/wpilibc/src/main/native/include/frc/PWM.h index cb9647dcc06..a7f174b9a3b 100644 --- a/wpilibc/src/main/native/include/frc/PWM.h +++ b/wpilibc/src/main/native/include/frc/PWM.h @@ -54,7 +54,6 @@ class PWM : public wpi::Sendable, public wpi::SendableHelper { * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the * MXP port * @param registerSendable If true, adds this instance to SendableRegistry - * and LiveWindow */ explicit PWM(int channel, bool registerSendable = true); diff --git a/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h b/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h deleted file mode 100644 index 2f0a34957ab..00000000000 --- a/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h +++ /dev/null @@ -1,90 +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. - -#pragma once - -#include - -namespace wpi { -class Sendable; -} // namespace wpi - -namespace frc { - -/** - * The LiveWindow class is the public interface for putting sensors and - * actuators on the LiveWindow. - */ -class LiveWindow final { - public: - /** - * Sets function to be called when LiveWindow is enabled. - * - * @param func function (or nullptr for none) - */ - static void SetEnabledCallback(std::function func); - - /** - * Sets function to be called when LiveWindow is disabled. - * - * @param func function (or nullptr for none) - */ - static void SetDisabledCallback(std::function func); - - /** - * Enable telemetry for a single component. - * - * @param component sendable - */ - static void EnableTelemetry(wpi::Sendable* component); - - /** - * Disable telemetry for a single component. - * - * @param component sendable - */ - static void DisableTelemetry(wpi::Sendable* component); - - /** - * Disable ALL telemetry. - */ - static void DisableAllTelemetry(); - - /** - * Enable ALL telemetry. - */ - static void EnableAllTelemetry(); - - /** - * Returns true if LiveWindow is enabled. - * - * @return True if LiveWindow is enabled. - */ - static bool IsEnabled(); - - /** - * Change the enabled status of LiveWindow. - * - * If it changes to enabled, start livewindow running otherwise stop it - */ - static void SetEnabled(bool enabled); - - /** - * Tell all the sensors to update (send) their values. - * - * Actuators are handled through callbacks on their value changing from the - * SmartDashboard widgets. - */ - static void UpdateValues(); - - private: - LiveWindow() = default; - - /** - * Updates the entries, without using a mutex or lock. - */ - static void UpdateValuesUnsafe(); -}; - -} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h index 2051d1b5d59..026c77ba0c1 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h @@ -73,18 +73,6 @@ class SendableBuilderImpl : public nt::NTSendableBuilder { */ void StopListeners(); - /** - * Start LiveWindow mode by hooking the setters for all properties. Also - * calls the SafeState function if one was provided. - */ - void StartLiveWindowMode(); - - /** - * Stop LiveWindow mode by unhooking the setters for all properties. Also - * calls the SafeState function if one was provided. - */ - void StopLiveWindowMode(); - /** * Clear properties. */ @@ -92,7 +80,6 @@ class SendableBuilderImpl : public nt::NTSendableBuilder { void SetSmartDashboardType(std::string_view type) override; void SetActuator(bool value) override; - void SetSafeState(std::function func) override; void SetUpdateTable(wpi::unique_function func) override; nt::Topic GetTopic(std::string_view key) override; @@ -238,7 +225,6 @@ class SendableBuilderImpl : public nt::NTSendableBuilder { void AddSmallPropertyImpl(Topic topic, Getter getter, Setter setter); std::vector> m_properties; - std::function m_safeState; std::vector> m_updateTables; std::shared_ptr m_table; bool m_controllable = false; diff --git a/wpilibc/src/test/native/cpp/TimedRobotTest.cpp b/wpilibc/src/test/native/cpp/TimedRobotTest.cpp index d639ecce078..f25964a6f32 100644 --- a/wpilibc/src/test/native/cpp/TimedRobotTest.cpp +++ b/wpilibc/src/test/native/cpp/TimedRobotTest.cpp @@ -11,7 +11,6 @@ #include -#include "frc/livewindow/LiveWindow.h" #include "frc/simulation/DriverStationSim.h" #include "frc/simulation/SimHooks.h" @@ -20,7 +19,7 @@ using namespace frc; inline constexpr auto kPeriod = 20_ms; namespace { -class TimedRobotTest : public ::testing::TestWithParam { +class TimedRobotTest : public ::testing::Test { protected: void SetUp() override { frc::sim::PauseTiming(); } @@ -308,12 +307,8 @@ TEST_F(TimedRobotTest, TeleopMode) { robotThread.join(); } -TEST_P(TimedRobotTest, TestMode) { - bool isTestLW = GetParam(); - +TEST_F(TimedRobotTest, TestMode) { MockRobot robot; - robot.EnableLiveWindowInTest(isTestLW); - std::thread robotThread{[&] { robot.StartCompetition(); }}; frc::sim::DriverStationSim::SetEnabled(true); @@ -328,7 +323,6 @@ TEST_P(TimedRobotTest, TestMode) { EXPECT_EQ(0u, robot.m_autonomousInitCount); EXPECT_EQ(0u, robot.m_teleopInitCount); EXPECT_EQ(0u, robot.m_testInitCount); - EXPECT_FALSE(frc::LiveWindow::IsEnabled()); EXPECT_EQ(0u, robot.m_robotPeriodicCount); EXPECT_EQ(0u, robot.m_simulationPeriodicCount); @@ -350,9 +344,6 @@ TEST_P(TimedRobotTest, TestMode) { EXPECT_EQ(0u, robot.m_autonomousInitCount); EXPECT_EQ(0u, robot.m_teleopInitCount); EXPECT_EQ(1u, robot.m_testInitCount); - EXPECT_EQ(isTestLW, frc::LiveWindow::IsEnabled()); - - EXPECT_THROW(robot.EnableLiveWindowInTest(isTestLW), std::runtime_error); EXPECT_EQ(1u, robot.m_robotPeriodicCount); EXPECT_EQ(1u, robot.m_simulationPeriodicCount); @@ -399,7 +390,6 @@ TEST_P(TimedRobotTest, TestMode) { EXPECT_EQ(0u, robot.m_autonomousInitCount); EXPECT_EQ(0u, robot.m_teleopInitCount); EXPECT_EQ(1u, robot.m_testInitCount); - EXPECT_FALSE(frc::LiveWindow::IsEnabled()); EXPECT_EQ(3u, robot.m_robotPeriodicCount); EXPECT_EQ(3u, robot.m_simulationPeriodicCount); @@ -609,5 +599,3 @@ TEST_F(TimedRobotTest, AddPeriodicWithOffset) { robot.EndCompetition(); robotThread.join(); } - -INSTANTIATE_TEST_SUITE_P(TimedRobotTests, TimedRobotTest, testing::Bool()); diff --git a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp index 50dbd4eeeb7..a10a421ba52 100644 --- a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp @@ -6,7 +6,6 @@ #include #include -#include #include #include @@ -45,14 +44,12 @@ void Robot::StartCompetition() { wpi::WaitForObject(event.GetHandle()); } } else if (IsTest()) { - frc::LiveWindow::SetEnabled(true); modeThread.InTest(true); Test(); modeThread.InTest(false); while (IsTest() && IsEnabled()) { wpi::WaitForObject(event.GetHandle()); } - frc::LiveWindow::SetEnabled(false); } else { modeThread.InTeleop(true); Teleop(); diff --git a/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp index 7f79b234965..600204afb3b 100644 --- a/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp @@ -4,16 +4,11 @@ #include "Robot.h" -#include #include #include // Run robot periodic() functions for 5 ms, and run controllers every 10 ms Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} { - // LiveWindow causes drastic overruns in robot periodic functions that will - // interfere with controllers - frc::LiveWindow::DisableAllTelemetry(); - // Runs for 2 ms after robot periodic functions Schedule([=] {}, 2_ms); diff --git a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp index 1a4f064affb..a76217a0db4 100644 --- a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp @@ -4,14 +4,8 @@ #include "Robot.h" -#include - // Run robot periodic() functions for 5 ms, and run controllers every 10 ms Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} { - // LiveWindow causes drastic overruns in robot periodic functions that will - // interfere with controllers - frc::LiveWindow::DisableAllTelemetry(); - // Runs for 2 ms after robot periodic functions Schedule([=] {}, 2_ms); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java index 19ce55555e0..b898b3ea8ec 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java @@ -135,7 +135,7 @@ public ADXL345_I2C(I2C.Port port, Range range, int deviceAddress) { setRange(range); HAL.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C); - SendableRegistry.addLW(this, "ADXL345_I2C", port.value); + SendableRegistry.add(this, "ADXL345_I2C", port.value); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java index 0bdb2ffa2f6..27a1213998d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java @@ -26,7 +26,7 @@ public class AnalogAccelerometer implements Sendable, AutoCloseable { /** Common initialization. */ private void initAccelerometer() { HAL.report(tResourceType.kResourceType_Accelerometer, m_analogChannel.getChannel() + 1); - SendableRegistry.addLW(this, "Accelerometer", m_analogChannel.getChannel()); + SendableRegistry.add(this, "Accelerometer", m_analogChannel.getChannel()); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java index 9d50a208a92..c455f4c2f67 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java @@ -83,7 +83,7 @@ private void init(double fullRange, double expectedZero) { m_fullRange = fullRange; m_expectedZero = expectedZero; - SendableRegistry.addLW(this, "Analog Encoder", m_analogInput.getChannel()); + SendableRegistry.add(this, "Analog Encoder", m_analogInput.getChannel()); } private double mapSensorRange(double pos) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java index 1628bf78785..2bca5771896 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java @@ -29,7 +29,7 @@ public class AnalogGyro implements Sendable, AutoCloseable { /** Initialize the gyro. Calibration is handled by calibrate(). */ private void initGyro() { HAL.report(tResourceType.kResourceType_Gyro, m_analog.getChannel() + 1); - SendableRegistry.addLW(this, "AnalogGyro", m_analog.getChannel()); + SendableRegistry.add(this, "AnalogGyro", m_analog.getChannel()); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java index e3a786bc951..e17721f9179 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java @@ -42,7 +42,7 @@ public AnalogInput(final int channel) { m_port = AnalogJNI.initializeAnalogInputPort(portHandle); HAL.report(tResourceType.kResourceType_AnalogChannel, channel + 1); - SendableRegistry.addLW(this, "AnalogInput", channel); + SendableRegistry.add(this, "AnalogInput", channel); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java index 15473495528..b7c32b23909 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java @@ -56,7 +56,7 @@ public AnalogPotentiometer(final int channel, double fullRange, double offset) { */ @SuppressWarnings("this-escape") public AnalogPotentiometer(final AnalogInput input, double fullRange, double offset) { - SendableRegistry.addLW(this, "AnalogPotentiometer", input.getChannel()); + SendableRegistry.add(this, "AnalogPotentiometer", input.getChannel()); m_analogInput = input; m_initAnalogInput = false; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java index 10949a88236..a205e503368 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java @@ -52,7 +52,7 @@ public AnalogTrigger(AnalogInput channel) { int index = getIndex(); HAL.report(tResourceType.kResourceType_AnalogTrigger, index + 1); - SendableRegistry.addLW(this, "AnalogTrigger", index); + SendableRegistry.add(this, "AnalogTrigger", index); } /** @@ -69,7 +69,7 @@ public AnalogTrigger(DutyCycle input) { int index = getIndex(); HAL.report(tResourceType.kResourceType_AnalogTrigger, index + 1); - SendableRegistry.addLW(this, "AnalogTrigger", index); + SendableRegistry.add(this, "AnalogTrigger", index); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java index 38dee091285..b43a3949e67 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java @@ -45,7 +45,7 @@ public Compressor(int module, PneumaticsModuleType moduleType) { m_module.enableCompressorDigital(); HAL.report(tResourceType.kResourceType_Compressor, module + 1); - SendableRegistry.addLW(this, "Compressor", module); + SendableRegistry.add(this, "Compressor", module); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java index c4bc1738777..f984aa0b67f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java @@ -85,7 +85,7 @@ public Counter(final Mode mode) { setMaxPeriod(0.5); HAL.report(tResourceType.kResourceType_Counter, m_index + 1, mode.value + 1); - SendableRegistry.addLW(this, "Counter", m_index); + SendableRegistry.add(this, "Counter", m_index); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java index ab3d5e5e4c7..edd91cdebdb 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java @@ -35,7 +35,7 @@ public DigitalInput(int channel) { m_handle = DIOJNI.initializeDIOPort(HAL.getPort((byte) channel), true); HAL.report(tResourceType.kResourceType_DigitalInput, channel + 1); - SendableRegistry.addLW(this, "DigitalInput", channel); + SendableRegistry.add(this, "DigitalInput", channel); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java index a7446f6068b..87ed908c94b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java @@ -37,7 +37,7 @@ public DigitalOutput(int channel) { m_handle = DIOJNI.initializeDIOPort(HAL.getPort((byte) channel), false); HAL.report(tResourceType.kResourceType_DigitalOutput, channel + 1); - SendableRegistry.addLW(this, "DigitalOutput", channel); + SendableRegistry.add(this, "DigitalOutput", channel); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java index aab8b1e1060..73eae77a2f9 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -99,7 +99,7 @@ public DoubleSolenoid( tResourceType.kResourceType_Solenoid, forwardChannel + 1, m_module.getModuleNumber() + 1); HAL.report( tResourceType.kResourceType_Solenoid, reverseChannel + 1, m_module.getModuleNumber() + 1); - SendableRegistry.addLW(this, "DoubleSolenoid", m_module.getModuleNumber(), forwardChannel); + SendableRegistry.add(this, "DoubleSolenoid", m_module.getModuleNumber(), forwardChannel); successfulCompletion = true; } finally { if (!successfulCompletion) { @@ -210,7 +210,6 @@ public boolean isRevSolenoidDisabled() { public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Double Solenoid"); builder.setActuator(true); - builder.setSafeState(() -> set(Value.kOff)); builder.addStringProperty( "Value", () -> get().name().substring(1), diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java index 342b87ef798..22ded084ac0 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java @@ -36,7 +36,7 @@ public DutyCycle(int channel) { m_channel = channel; HAL.report(tResourceType.kResourceType_DutyCycle, channel + 1); - SendableRegistry.addLW(this, "Duty Cycle", channel); + SendableRegistry.add(this, "Duty Cycle", channel); } /** Close the DutyCycle and free all resources. */ diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java index 4b4b44d5818..e5e58fe8c90 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java @@ -93,7 +93,7 @@ private void init(double fullRange, double expectedZero) { m_fullRange = fullRange; m_expectedZero = expectedZero; - SendableRegistry.addLW(this, "DutyCycle Encoder", m_dutyCycle.getSourceChannel()); + SendableRegistry.add(this, "DutyCycle Encoder", m_dutyCycle.getSourceChannel()); } private double mapSensorRange(double pos) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java index 76b0b4bb10d..c851de15d07 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java @@ -84,7 +84,7 @@ private void initEncoder(boolean reverseDirection, final EncodingType type) { int fpgaIndex = getFPGAIndex(); HAL.report(tResourceType.kResourceType_Encoder, fpgaIndex + 1, type.value + 1); - SendableRegistry.addLW(this, "Encoder", fpgaIndex); + SendableRegistry.add(this, "Encoder", fpgaIndex); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java index ed4d9de959f..2d136585f52 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java @@ -5,13 +5,9 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.DriverStationJNI; -import edu.wpi.first.hal.FRCNetComm.tInstances; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.networktables.NetworkTableInstance; -import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import java.util.ConcurrentModificationException; /** * IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase @@ -71,7 +67,6 @@ private enum Mode { private final double m_period; private final Watchdog m_watchdog; private boolean m_ntFlushEnabled = true; - private boolean m_lwEnabledInTest; private boolean m_calledDsConnected; /** @@ -259,34 +254,6 @@ public void setNetworkTablesFlushEnabled(boolean enabled) { m_ntFlushEnabled = enabled; } - private boolean m_reportedLw; - - /** - * Sets whether LiveWindow operation is enabled during test mode. Calling - * - * @param testLW True to enable, false to disable. Defaults to false. - * @throws ConcurrentModificationException if this is called during test mode. - */ - public void enableLiveWindowInTest(boolean testLW) { - if (isTestEnabled()) { - throw new ConcurrentModificationException("Can't configure test mode while in test mode!"); - } - if (!m_reportedLw && testLW) { - HAL.report(tResourceType.kResourceType_SmartDashboard, tInstances.kSmartDashboard_LiveWindow); - m_reportedLw = true; - } - m_lwEnabledInTest = testLW; - } - - /** - * Whether LiveWindow operation is enabled during test mode. - * - * @return whether LiveWindow should be enabled in test mode. - */ - public boolean isLiveWindowEnabledInTest() { - return m_lwEnabledInTest; - } - /** * Gets time period between calls to Periodic() functions. * @@ -327,12 +294,7 @@ protected void loopFunc() { case kDisabled -> disabledExit(); case kAutonomous -> autonomousExit(); case kTeleop -> teleopExit(); - case kTest -> { - if (m_lwEnabledInTest) { - LiveWindow.setEnabled(false); - } - testExit(); - } + case kTest -> testExit(); default -> { // NOP } @@ -353,9 +315,6 @@ protected void loopFunc() { m_watchdog.addEpoch("teleopInit()"); } case kTest -> { - if (m_lwEnabledInTest) { - LiveWindow.setEnabled(true); - } testInit(); m_watchdog.addEpoch("testInit()"); } @@ -399,8 +358,6 @@ protected void loopFunc() { SmartDashboard.updateValues(); m_watchdog.addEpoch("SmartDashboard.updateValues()"); - LiveWindow.updateValues(); - m_watchdog.addEpoch("LiveWindow.updateValues()"); if (isSimulation()) { HAL.simPeriodicBefore(); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java index fa4218a0235..460424abfba 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java @@ -40,7 +40,7 @@ public enum PeriodMultiplier { *

Checks channel value range and allocates the appropriate channel. The allocation is only * done to help users ensure that they don't double assign channels. * - *

By default, adds itself to SendableRegistry and LiveWindow. + *

By default, adds itself to SendableRegistry. * * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port */ @@ -52,7 +52,7 @@ public PWM(final int channel) { * Allocate a PWM given a channel. * * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port - * @param registerSendable If true, adds this instance to SendableRegistry and LiveWindow + * @param registerSendable If true, adds this instance to SendableRegistry */ @SuppressWarnings("this-escape") public PWM(final int channel, final boolean registerSendable) { @@ -67,7 +67,7 @@ public PWM(final int channel, final boolean registerSendable) { HAL.report(tResourceType.kResourceType_PWM, channel + 1); if (registerSendable) { - SendableRegistry.addLW(this, "PWM", channel); + SendableRegistry.add(this, "PWM", channel); } } @@ -244,7 +244,6 @@ public int getHandle() { public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("PWM"); builder.setActuator(true); - builder.setSafeState(this::setDisabled); builder.addDoubleProperty( "Value", this::getPulseTimeMicroseconds, value -> setPulseTimeMicroseconds((int) value)); builder.addDoubleProperty("Speed", this::getSpeed, this::setSpeed); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java index 15f8e0ec246..e26c8a2d865 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java @@ -57,7 +57,7 @@ public PowerDistribution(int module, ModuleType moduleType) { } else { HAL.report(tResourceType.kResourceType_PDP, tInstances.kPDP_REV); } - SendableRegistry.addLW(this, "PowerDistribution", m_module); + SendableRegistry.add(this, "PowerDistribution", m_module); } /** @@ -76,7 +76,7 @@ public PowerDistribution() { HAL.report(tResourceType.kResourceType_PDP, tInstances.kPDP_REV); } - SendableRegistry.addLW(this, "PowerDistribution", m_module); + SendableRegistry.add(this, "PowerDistribution", m_module); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java index 775562e293c..193c5f74492 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java @@ -17,7 +17,6 @@ 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; import edu.wpi.first.wpilibj.util.WPILibVersion; import java.io.File; import java.io.IOException; @@ -224,8 +223,6 @@ protected RobotBase() { } } }); - - LiveWindow.setEnabled(false); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java index 66993da1b2f..98317a099c6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java @@ -89,7 +89,7 @@ public SharpIR(int channel, double a, double b, double minCM, double maxCM) { m_minCM = minCM; m_maxCM = maxCM; - SendableRegistry.addLW(this, "SharpIR", channel); + SendableRegistry.add(this, "SharpIR", channel); m_simDevice = SimDevice.create("SharpIR", m_sensor.getChannel()); if (m_simDevice != null) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index 9c516da72f2..6f78a6130a7 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -57,7 +57,7 @@ public Solenoid(final int module, final PneumaticsModuleType moduleType, final i } HAL.report(tResourceType.kResourceType_Solenoid, channel + 1, m_module.getModuleNumber() + 1); - SendableRegistry.addLW(this, "Solenoid", m_module.getModuleNumber(), channel); + SendableRegistry.add(this, "Solenoid", m_module.getModuleNumber(), channel); } @Override @@ -148,7 +148,6 @@ public void startPulse() { public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Solenoid"); builder.setActuator(true); - builder.setSafeState(() -> set(false)); builder.addBooleanProperty("Value", this::get, this::set); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java index 14103544ce3..bfd5903662c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java @@ -107,7 +107,7 @@ private synchronized void initialize() { m_instances++; HAL.report(tResourceType.kResourceType_Ultrasonic, m_instances); - SendableRegistry.addLW(this, "Ultrasonic", m_echoChannel.getChannel()); + SendableRegistry.add(this, "Ultrasonic", m_echoChannel.getChannel()); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java index 97fbf5b464d..fb78ff5f821 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java @@ -60,7 +60,7 @@ public ExternalDirectionCounter(DigitalSource countSource, DigitalSource directi int intIndex = index.getInt(); HAL.report(tResourceType.kResourceType_Counter, intIndex + 1); - SendableRegistry.addLW(this, "External Direction Counter", intIndex); + SendableRegistry.add(this, "External Direction Counter", intIndex); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java index 6bef24deaa7..cba2c92444a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java @@ -49,7 +49,7 @@ public Tachometer(DigitalSource source) { int intIndex = index.getInt(); HAL.report(tResourceType.kResourceType_Counter, intIndex + 1); - SendableRegistry.addLW(this, "Tachometer", intIndex); + SendableRegistry.add(this, "Tachometer", intIndex); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java index ed9f35e971f..603a5cd921d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java @@ -63,7 +63,7 @@ public UpDownCounter(DigitalSource upSource, DigitalSource downSource) { int intIndex = index.getInt(); HAL.report(tResourceType.kResourceType_Counter, intIndex + 1); - SendableRegistry.addLW(this, "UpDown Counter", intIndex); + SendableRegistry.add(this, "UpDown Counter", intIndex); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java index 40e34a803da..dba563305f9 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java @@ -127,7 +127,7 @@ public DifferentialDrive(DoubleConsumer leftMotor, DoubleConsumer rightMotor) { m_leftMotor = leftMotor; m_rightMotor = rightMotor; instances++; - SendableRegistry.addLW(this, "DifferentialDrive", instances); + SendableRegistry.add(this, "DifferentialDrive", instances); } @Override @@ -367,7 +367,6 @@ public String getDescription() { public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("DifferentialDrive"); builder.setActuator(true); - builder.setSafeState(this::stopMotor); builder.addDoubleProperty("Left Motor Speed", () -> m_leftOutput, m_leftMotor); builder.addDoubleProperty("Right Motor Speed", () -> m_rightOutput, m_rightMotor); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java index df043622722..9250aba6fae 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java @@ -158,7 +158,7 @@ public MecanumDrive( m_frontRightMotor = frontRightMotor; m_rearRightMotor = rearRightMotor; instances++; - SendableRegistry.addLW(this, "MecanumDrive", instances); + SendableRegistry.add(this, "MecanumDrive", instances); } @Override @@ -317,7 +317,6 @@ public String getDescription() { public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("MecanumDrive"); builder.setActuator(true); - builder.setSafeState(this::stopMotor); builder.addDoubleProperty("Front Left Motor Speed", () -> m_frontLeftOutput, m_frontLeftMotor); builder.addDoubleProperty( "Front Right Motor Speed", () -> m_frontRightOutput, m_frontRightMotor); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java deleted file mode 100644 index f30ac59d178..00000000000 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java +++ /dev/null @@ -1,247 +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. - -package edu.wpi.first.wpilibj.livewindow; - -import edu.wpi.first.networktables.BooleanPublisher; -import edu.wpi.first.networktables.NetworkTable; -import edu.wpi.first.networktables.NetworkTableInstance; -import edu.wpi.first.networktables.StringPublisher; -import edu.wpi.first.networktables.StringTopic; -import edu.wpi.first.util.sendable.Sendable; -import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl; - -/** - * The LiveWindow class is the public interface for putting sensors and actuators on the LiveWindow. - */ -public final class LiveWindow { - private static final class Component implements AutoCloseable { - @Override - public void close() { - if (m_namePub != null) { - m_namePub.close(); - m_namePub = null; - } - if (m_typePub != null) { - m_typePub.close(); - m_typePub = null; - } - } - - boolean m_firstTime = true; - boolean m_telemetryEnabled; - StringPublisher m_namePub; - StringPublisher m_typePub; - } - - private static final String kSmartDashboardType = "LW Subsystem"; - - private static final int dataHandle = SendableRegistry.getDataHandle(); - private static final NetworkTable liveWindowTable = - NetworkTableInstance.getDefault().getTable("LiveWindow"); - private static final NetworkTable statusTable = liveWindowTable.getSubTable(".status"); - private static final BooleanPublisher enabledPub = - statusTable.getBooleanTopic("LW Enabled").publish(); - private static boolean startLiveWindow; - private static boolean liveWindowEnabled; - private static boolean telemetryEnabled; - - private static Runnable enabledListener; - private static Runnable disabledListener; - - static { - SendableRegistry.setLiveWindowBuilderFactory(SendableBuilderImpl::new); - enabledPub.set(false); - } - - private static Component getOrAdd(Sendable sendable) { - Component data = (Component) SendableRegistry.getData(sendable, dataHandle); - if (data == null) { - data = new Component(); - SendableRegistry.setData(sendable, dataHandle, data); - } - return data; - } - - private LiveWindow() { - throw new UnsupportedOperationException("This is a utility class!"); - } - - /** - * Sets function to be called when LiveWindow is enabled. - * - * @param runnable function (or null for none) - */ - public static synchronized void setEnabledListener(Runnable runnable) { - enabledListener = runnable; - } - - /** - * Sets function to be called when LiveWindow is disabled. - * - * @param runnable function (or null for none) - */ - public static synchronized void setDisabledListener(Runnable runnable) { - disabledListener = runnable; - } - - /** - * Returns true if LiveWindow is enabled. - * - * @return True if LiveWindow is enabled. - */ - public static synchronized boolean isEnabled() { - return liveWindowEnabled; - } - - /** - * Set the enabled state of LiveWindow. - * - *

If it's being enabled, turn off the scheduler and remove all the commands from the queue and - * enable all the components registered for LiveWindow. If it's being disabled, stop all the - * registered components and re-enable the scheduler. - * - *

TODO: add code to disable PID loops when enabling LiveWindow. The commands should re-enable - * the PID loops themselves when they get rescheduled. This prevents arms from starting to move - * around, etc. after a period of adjusting them in LiveWindow mode. - * - * @param enabled True to enable LiveWindow. - */ - public static synchronized void setEnabled(boolean enabled) { - if (liveWindowEnabled != enabled) { - startLiveWindow = enabled; - liveWindowEnabled = enabled; - updateValues(); // Force table generation now to make sure everything is defined - if (enabled) { - System.out.println("Starting live window mode."); - if (enabledListener != null) { - enabledListener.run(); - } - } else { - System.out.println("stopping live window mode."); - SendableRegistry.foreachLiveWindow( - dataHandle, cbdata -> ((SendableBuilderImpl) cbdata.builder).stopLiveWindowMode()); - if (disabledListener != null) { - disabledListener.run(); - } - } - enabledPub.set(enabled); - } - } - - /** - * Enable telemetry for a single component. - * - * @param sendable component - */ - public static synchronized void enableTelemetry(Sendable sendable) { - // Re-enable global setting in case disableAllTelemetry() was called. - telemetryEnabled = true; - getOrAdd(sendable).m_telemetryEnabled = true; - } - - /** - * Disable telemetry for a single component. - * - * @param sendable component - */ - public static synchronized void disableTelemetry(Sendable sendable) { - getOrAdd(sendable).m_telemetryEnabled = false; - } - - /** Disable ALL telemetry. */ - public static synchronized void disableAllTelemetry() { - telemetryEnabled = false; - SendableRegistry.foreachLiveWindow( - dataHandle, - cbdata -> { - if (cbdata.data == null) { - cbdata.data = new Component(); - } - ((Component) cbdata.data).m_telemetryEnabled = false; - }); - } - - /** Enable ALL telemetry. */ - public static synchronized void enableAllTelemetry() { - telemetryEnabled = true; - SendableRegistry.foreachLiveWindow( - dataHandle, - cbdata -> { - if (cbdata.data == null) { - cbdata.data = new Component(); - } - ((Component) cbdata.data).m_telemetryEnabled = true; - }); - } - - /** - * Tell all the sensors to update (send) their values. - * - *

Actuators are handled through callbacks on their value changing from the SmartDashboard - * widgets. - */ - public static synchronized void updateValues() { - // Only do this if either LiveWindow mode or telemetry is enabled. - if (!liveWindowEnabled && !telemetryEnabled) { - return; - } - - SendableRegistry.foreachLiveWindow( - dataHandle, - cbdata -> { - if (cbdata.sendable == null || cbdata.parent != null) { - return; - } - - if (cbdata.data == null) { - cbdata.data = new Component(); - } - - Component component = (Component) cbdata.data; - - if (!liveWindowEnabled && !component.m_telemetryEnabled) { - return; - } - - if (component.m_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.isEmpty()) { - return; - } - NetworkTable ssTable = liveWindowTable.getSubTable(cbdata.subsystem); - NetworkTable table; - // Treat name==subsystem as top level of subsystem - if (cbdata.name.equals(cbdata.subsystem)) { - table = ssTable; - } else { - table = ssTable.getSubTable(cbdata.name); - } - component.m_namePub = new StringTopic(table.getTopic(".name")).publish(); - component.m_namePub.set(cbdata.name); - ((SendableBuilderImpl) cbdata.builder).setTable(table); - cbdata.sendable.initSendable(cbdata.builder); - component.m_typePub = - new StringTopic(ssTable.getTopic(".type")) - .publishEx( - StringTopic.kTypeString, - "{\"SmartDashboard\":\"" + kSmartDashboardType + "\"}"); - component.m_typePub.set(kSmartDashboardType); - - component.m_firstTime = false; - } - - if (startLiveWindow) { - ((SendableBuilderImpl) cbdata.builder).startLiveWindowMode(); - } - cbdata.builder.update(); - }); - - startLiveWindow = false; - } -} diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java index c56496cd480..d0322ead838 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java @@ -53,7 +53,7 @@ private void init() { SendableRegistry.addChild(this, controller); } instances++; - SendableRegistry.addLW(this, "MotorControllerGroup", instances); + SendableRegistry.add(this, "MotorControllerGroup", instances); } @Override @@ -111,7 +111,6 @@ public void stopMotor() { public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Motor Controller"); builder.setActuator(true); - builder.setSafeState(this::stopMotor); builder.addDoubleProperty("Value", this::get, this::set); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java index 01af76563cb..0f3d5ad95ec 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java @@ -46,7 +46,7 @@ public NidecBrushless(final int pwmChannel, final int dioChannel) { SendableRegistry.addChild(this, m_pwm); HAL.report(tResourceType.kResourceType_NidecBrushless, pwmChannel + 1); - SendableRegistry.addLW(this, "Nidec Brushless", pwmChannel); + SendableRegistry.add(this, "Nidec Brushless", pwmChannel); } @Override @@ -139,7 +139,6 @@ public int getChannel() { public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Nidec Brushless"); builder.setActuator(true); - builder.setSafeState(this::stopMotor); builder.addDoubleProperty("Value", this::get, this::set); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java index 803f57d73b5..6ebd8f9c861 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java @@ -32,7 +32,7 @@ public abstract class PWMMotorController extends MotorSafety @SuppressWarnings("this-escape") protected PWMMotorController(final String name, final int channel) { m_pwm = new PWM(channel, false); - SendableRegistry.addLW(this, name, channel); + SendableRegistry.add(this, name, channel); } /** Free the resource associated with the PWM channel and set the value to 0. */ @@ -161,7 +161,6 @@ public void addFollower(PWMMotorController follower) { public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Motor Controller"); builder.setActuator(true); - builder.setSafeState(this::disable); builder.addDoubleProperty("Value", this::get, this::set); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java index 09a16860e53..f38293d88df 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java @@ -98,7 +98,6 @@ void update(boolean controllable, long time) { } private final List> m_properties = new ArrayList<>(); - private Runnable m_safeState; private final List m_updateTables = new ArrayList<>(); private NetworkTable m_table; private boolean m_controllable; @@ -205,28 +204,6 @@ public void stopListeners() { } } - /** - * Start LiveWindow mode by hooking the setters for all properties. Also calls the safeState - * function if one was provided. - */ - public void startLiveWindowMode() { - if (m_safeState != null) { - m_safeState.run(); - } - startListeners(); - } - - /** - * Stop LiveWindow mode by unhooking the setters for all properties. Also calls the safeState - * function if one was provided. - */ - public void stopLiveWindowMode() { - stopListeners(); - if (m_safeState != null) { - m_safeState.run(); - } - } - /** Clear properties. */ @Override public void clearProperties() { @@ -274,17 +251,6 @@ public void setActuator(boolean value) { m_actuator = value; } - /** - * Set the function that should be called to set the Sendable into a safe state. This is called - * when entering and exiting Live Window mode. - * - * @param func function - */ - @Override - public void setSafeState(Runnable func) { - m_safeState = func; - } - /** * Set the function that should be called to update the network table for things other than * properties. Note this function is not passed the network table object; instead it should use diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java index da0bd92bdb3..1d3f0e70e6e 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java @@ -5,20 +5,14 @@ package edu.wpi.first.wpilibj; import static org.junit.jupiter.api.Assertions.assertEquals; -import static org.junit.jupiter.api.Assertions.assertFalse; -import static org.junit.jupiter.api.Assertions.assertThrows; -import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.simulation.DriverStationSim; import edu.wpi.first.wpilibj.simulation.SimHooks; -import java.util.ConcurrentModificationException; import java.util.concurrent.atomic.AtomicInteger; import org.junit.jupiter.api.AfterEach; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; import org.junit.jupiter.api.parallel.ResourceLock; -import org.junit.jupiter.params.ParameterizedTest; -import org.junit.jupiter.params.provider.ValueSource; class TimedRobotTest { static final double kPeriod = 0.02; @@ -389,12 +383,10 @@ void teleopModeTest() { robot.close(); } - @ValueSource(booleans = {true, false}) - @ParameterizedTest + @Test @ResourceLock("timing") - void testModeTest(boolean isLW) { + void testModeTest() { MockRobot robot = new MockRobot(); - robot.enableLiveWindowInTest(isLW); Thread robotThread = new Thread(robot::startCompetition); robotThread.start(); @@ -411,7 +403,6 @@ void testModeTest(boolean isLW) { assertEquals(0, robot.m_autonomousInitCount.get()); assertEquals(0, robot.m_teleopInitCount.get()); assertEquals(0, robot.m_testInitCount.get()); - assertFalse(LiveWindow.isEnabled()); assertEquals(0, robot.m_robotPeriodicCount.get()); assertEquals(0, robot.m_simulationPeriodicCount.get()); @@ -454,9 +445,6 @@ void testModeTest(boolean isLW) { assertEquals(0, robot.m_autonomousInitCount.get()); assertEquals(0, robot.m_teleopInitCount.get()); assertEquals(1, robot.m_testInitCount.get()); - assertEquals(isLW, LiveWindow.isEnabled()); - - assertThrows(ConcurrentModificationException.class, () -> robot.enableLiveWindowInTest(isLW)); assertEquals(2, robot.m_robotPeriodicCount.get()); assertEquals(2, robot.m_simulationPeriodicCount.get()); @@ -483,7 +471,6 @@ void testModeTest(boolean isLW) { assertEquals(0, robot.m_autonomousInitCount.get()); assertEquals(0, robot.m_teleopInitCount.get()); assertEquals(1, robot.m_testInitCount.get()); - assertFalse(LiveWindow.isEnabled()); assertEquals(3, robot.m_robotPeriodicCount.get()); assertEquals(3, robot.m_simulationPeriodicCount.get()); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/livewindow/LiveWindowTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/livewindow/LiveWindowTest.java deleted file mode 100644 index 869fb8c3765..00000000000 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/livewindow/LiveWindowTest.java +++ /dev/null @@ -1,14 +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. - -package edu.wpi.first.wpilibj.livewindow; - -import edu.wpi.first.wpilibj.UtilityClassTest; - -@SuppressWarnings("PMD.TestClassWithoutTestCases") -class LiveWindowTest extends UtilityClassTest { - LiveWindowTest() { - super(LiveWindow.class); - } -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timeslice/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timeslice/Robot.java index f33690c12dd..be7221f7a7e 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timeslice/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timeslice/Robot.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj.templates.timeslice; import edu.wpi.first.wpilibj.TimesliceRobot; -import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -25,10 +24,6 @@ public Robot() { // Run robot periodic() functions for 5 ms, and run controllers every 10 ms super(0.005, 0.01); - // LiveWindow causes drastic overruns in robot periodic functions that will - // interfere with controllers - LiveWindow.disableAllTelemetry(); - // Runs for 2 ms after robot periodic functions schedule(() -> {}, 0.002); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timesliceskeleton/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timesliceskeleton/Robot.java index d0a019efa19..665018ebc45 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timesliceskeleton/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timesliceskeleton/Robot.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj.templates.timesliceskeleton; import edu.wpi.first.wpilibj.TimesliceRobot; -import edu.wpi.first.wpilibj.livewindow.LiveWindow; /** * The methods in this class are called automatically corresponding to each mode, as described in @@ -18,10 +17,6 @@ public Robot() { // Run robot periodic() functions for 5 ms, and run controllers every 10 ms super(0.005, 0.01); - // LiveWindow causes drastic overruns in robot periodic functions that will - // interfere with controllers - LiveWindow.disableAllTelemetry(); - // Runs for 2 ms after robot periodic functions schedule(() -> {}, 0.002); diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java index b4d56996c06..3151e104b12 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java @@ -43,7 +43,7 @@ public BangBangController(double tolerance) { setTolerance(tolerance); - SendableRegistry.addLW(this, "BangBangController", instances); + SendableRegistry.add(this, "BangBangController", instances); MathSharedStore.reportUsage(MathUsageId.kController_BangBangController, instances); } diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java index 0bd71d4b187..dfdf4a2d3c9 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java @@ -109,7 +109,7 @@ public PIDController(double kp, double ki, double kd, double period) { m_period = period; instances++; - SendableRegistry.addLW(this, "PIDController", instances); + SendableRegistry.add(this, "PIDController", instances); MathSharedStore.reportUsage(MathUsageId.kController_PIDController2, instances); } diff --git a/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableBuilder.java b/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableBuilder.java index ee93725acd1..748f38508d9 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableBuilder.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableBuilder.java @@ -42,14 +42,6 @@ enum BackendKind { */ void setActuator(boolean value); - /** - * Set the function that should be called to set the Sendable into a safe state. This is called - * when entering and exiting Live Window mode. - * - * @param func function - */ - void setSafeState(Runnable func); - /** * Add a boolean property. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java b/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java index 025b802094d..7aaa512be40 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java @@ -5,17 +5,13 @@ package edu.wpi.first.util.sendable; import java.lang.ref.WeakReference; -import java.util.ArrayList; import java.util.Arrays; -import java.util.List; import java.util.Map; import java.util.WeakHashMap; -import java.util.function.Consumer; -import java.util.function.Supplier; /** * The SendableRegistry class is the public interface for registering sensors and actuators for use - * on dashboards and LiveWindow. + * on dashboards. */ @SuppressWarnings("PMD.AvoidCatchingGenericException") public final class SendableRegistry { @@ -40,8 +36,6 @@ public void close() throws Exception { SendableBuilder m_builder; String m_name; String m_subsystem = "Ungrouped"; - WeakReference m_parent; - boolean m_liveWindow; AutoCloseable[] m_data; void setName(String moduleType, int channel) { @@ -53,7 +47,6 @@ void setName(String moduleType, int moduleNumber, int channel) { } } - private static Supplier liveWindowFactory; private static final Map components = new WeakHashMap<>(); private static int nextDataHandle; @@ -74,15 +67,6 @@ private SendableRegistry() { throw new UnsupportedOperationException("This is a utility class!"); } - /** - * Sets the factory for LiveWindow builders. - * - * @param factory factory function - */ - public static synchronized void setLiveWindowBuilderFactory(Supplier factory) { - liveWindowFactory = factory; - } - /** * Adds an object to the registry. * @@ -133,100 +117,6 @@ public static synchronized void add(Sendable sendable, String subsystem, String comp.m_subsystem = subsystem; } - /** - * Adds an object to the registry and LiveWindow. - * - * @param sendable object to add - * @param name component name - */ - public static synchronized void addLW(Sendable sendable, String name) { - Component comp = getOrAdd(sendable); - if (liveWindowFactory != null) { - if (comp.m_builder != null) { - try { - comp.m_builder.close(); - } catch (Exception e) { - // ignore - } - } - comp.m_builder = liveWindowFactory.get(); - } - comp.m_liveWindow = true; - comp.m_name = name; - } - - /** - * Adds an object to the registry and LiveWindow. - * - * @param sendable object to add - * @param moduleType A string that defines the module name in the label for the value - * @param channel The channel number the device is plugged into - */ - public static synchronized void addLW(Sendable sendable, String moduleType, int channel) { - Component comp = getOrAdd(sendable); - if (liveWindowFactory != null) { - if (comp.m_builder != null) { - try { - comp.m_builder.close(); - } catch (Exception e) { - // ignore - } - } - comp.m_builder = liveWindowFactory.get(); - } - comp.m_liveWindow = true; - comp.setName(moduleType, channel); - } - - /** - * Adds an object to the registry and LiveWindow. - * - * @param sendable object to add - * @param moduleType A string that defines the module name in the label for the value - * @param moduleNumber The number of the particular module type - * @param channel The channel number the device is plugged into - */ - public static synchronized void addLW( - Sendable sendable, String moduleType, int moduleNumber, int channel) { - Component comp = getOrAdd(sendable); - if (liveWindowFactory != null) { - if (comp.m_builder != null) { - try { - comp.m_builder.close(); - } catch (Exception e) { - // ignore - } - } - comp.m_builder = liveWindowFactory.get(); - } - comp.m_liveWindow = true; - comp.setName(moduleType, moduleNumber, channel); - } - - /** - * Adds an object to the registry and LiveWindow. - * - * @param sendable object to add - * @param subsystem subsystem name - * @param name component name - */ - public static synchronized void addLW(Sendable sendable, String subsystem, String name) { - Component comp = getOrAdd(sendable); - if (liveWindowFactory != null) { - if (comp.m_builder != null) { - try { - comp.m_builder.close(); - } catch (Exception e) { - // ignore - } - } - comp.m_builder = liveWindowFactory.get(); - } - comp.m_liveWindow = true; - comp.m_name = name; - comp.m_subsystem = subsystem; - } - /** * Adds a child object to an object. Adds the child object to the registry if it's not already * present. @@ -240,7 +130,7 @@ public static synchronized void addChild(Sendable parent, Object child) { comp = new Component(); components.put(child, comp); } - comp.m_parent = new WeakReference<>(parent); + // comp.m_parent = new WeakReference<>(parent); } /** @@ -430,30 +320,6 @@ public static synchronized Object getData(Sendable sendable, int handle) { return comp.m_data[handle]; } - /** - * Enables LiveWindow for an object. - * - * @param sendable object - */ - public static synchronized void enableLiveWindow(Sendable sendable) { - Component comp = components.get(sendable); - if (comp != null) { - comp.m_liveWindow = true; - } - } - - /** - * Disables LiveWindow for an object. - * - * @param sendable object - */ - public static synchronized void disableLiveWindow(Sendable sendable) { - Component comp = components.get(sendable); - if (comp != null) { - comp.m_liveWindow = false; - } - } - /** * Publishes an object in the registry to a builder. * @@ -485,98 +351,4 @@ public static synchronized void update(Sendable sendable) { comp.m_builder.update(); } } - - /** Data passed to foreachLiveWindow() callback function. */ - @SuppressWarnings("MemberName") - public static class CallbackData { - /** Sendable object. */ - public Sendable sendable; - - /** Name. */ - public String name; - - /** Subsystem. */ - public String subsystem; - - /** Parent sendable object. */ - public Sendable parent; - - /** Data stored in object with setData(). Update this to change the data. */ - public AutoCloseable data; - - /** Sendable builder for the sendable. */ - public SendableBuilder builder; - - /** Default constructor. */ - public CallbackData() {} - } - - // As foreachLiveWindow is single threaded, cache the components it - // iterates over to avoid risk of ConcurrentModificationException - private static List foreachComponents = new ArrayList<>(); - - /** - * Iterates over LiveWindow-enabled objects in the registry. It is *not* safe to call other - * SendableRegistry functions from the callback. - * - * @param dataHandle data handle to get data object passed to callback - * @param callback function to call for each object - */ - @SuppressWarnings("PMD.CompareObjectsWithEquals") - public static synchronized void foreachLiveWindow( - int dataHandle, Consumer callback) { - CallbackData cbdata = new CallbackData(); - foreachComponents.clear(); - foreachComponents.addAll(components.values()); - for (Component comp : foreachComponents) { - if (comp.m_builder == null || comp.m_sendable == null) { - continue; - } - cbdata.sendable = comp.m_sendable.get(); - if (cbdata.sendable != null && comp.m_liveWindow) { - cbdata.name = comp.m_name; - cbdata.subsystem = comp.m_subsystem; - if (comp.m_parent != null) { - cbdata.parent = comp.m_parent.get(); - } else { - cbdata.parent = null; - } - if (comp.m_data != null && dataHandle < comp.m_data.length) { - cbdata.data = comp.m_data[dataHandle]; - } else { - cbdata.data = null; - } - cbdata.builder = comp.m_builder; - try { - callback.accept(cbdata); - } catch (Throwable throwable) { - Throwable cause = throwable.getCause(); - if (cause != null) { - throwable = cause; - } - System.err.println("Unhandled exception calling LiveWindow for " + comp.m_name + ": "); - throwable.printStackTrace(); - comp.m_liveWindow = false; - } - if (cbdata.data != null) { - if (comp.m_data == null) { - comp.m_data = new AutoCloseable[dataHandle + 1]; - } else if (dataHandle >= comp.m_data.length) { - comp.m_data = Arrays.copyOf(comp.m_data, dataHandle + 1); - } - if (comp.m_data[dataHandle] != cbdata.data) { - if (comp.m_data[dataHandle] != null) { - try { - comp.m_data[dataHandle].close(); - } catch (Exception e) { - // ignore - } - } - comp.m_data[dataHandle] = cbdata.data; - } - } - } - } - foreachComponents.clear(); - } } diff --git a/wpiutil/src/main/native/cpp/sendable/SendableRegistry.cpp b/wpiutil/src/main/native/cpp/sendable/SendableRegistry.cpp index 99ff7f5e1ab..74ec0e9e5a7 100644 --- a/wpiutil/src/main/native/cpp/sendable/SendableRegistry.cpp +++ b/wpiutil/src/main/native/cpp/sendable/SendableRegistry.cpp @@ -26,7 +26,6 @@ struct Component { std::string name; std::string subsystem = "Ungrouped"; Sendable* parent = nullptr; - bool liveWindow = false; wpi::SmallVector, 2> data; void SetName(std::string_view moduleType, int channel) { @@ -41,7 +40,6 @@ struct Component { struct SendableRegistryInst { wpi::recursive_mutex mutex; - std::function()> liveWindowFactory; wpi::UidVector, 32> components; wpi::DenseMap componentMap; int nextDataHandle = 0; @@ -85,11 +83,6 @@ void SendableRegistry::EnsureInitialized() { GetInstance(); } -void SendableRegistry::SetLiveWindowBuilderFactory( - std::function()> factory) { - GetInstance().liveWindowFactory = std::move(factory); -} - void SendableRegistry::Add(Sendable* sendable, std::string_view name) { auto& inst = GetInstance(); std::scoped_lock lock(inst.mutex); @@ -126,58 +119,6 @@ void SendableRegistry::Add(Sendable* sendable, std::string_view subsystem, comp.subsystem = subsystem; } -void SendableRegistry::AddLW(Sendable* sendable, std::string_view name) { - auto& inst = GetInstance(); - std::scoped_lock lock(inst.mutex); - auto& comp = inst.GetOrAdd(sendable); - comp.sendable = sendable; - if (inst.liveWindowFactory) { - comp.builder = inst.liveWindowFactory(); - } - comp.liveWindow = true; - comp.name = name; -} - -void SendableRegistry::AddLW(Sendable* sendable, std::string_view moduleType, - int channel) { - auto& inst = GetInstance(); - std::scoped_lock lock(inst.mutex); - auto& comp = inst.GetOrAdd(sendable); - comp.sendable = sendable; - if (inst.liveWindowFactory) { - comp.builder = inst.liveWindowFactory(); - } - comp.liveWindow = true; - comp.SetName(moduleType, channel); -} - -void SendableRegistry::AddLW(Sendable* sendable, std::string_view moduleType, - int moduleNumber, int channel) { - auto& inst = GetInstance(); - std::scoped_lock lock(inst.mutex); - auto& comp = inst.GetOrAdd(sendable); - comp.sendable = sendable; - if (inst.liveWindowFactory) { - comp.builder = inst.liveWindowFactory(); - } - comp.liveWindow = true; - comp.SetName(moduleType, moduleNumber, channel); -} - -void SendableRegistry::AddLW(Sendable* sendable, std::string_view subsystem, - std::string_view name) { - auto& inst = GetInstance(); - std::scoped_lock lock(inst.mutex); - auto& comp = inst.GetOrAdd(sendable); - comp.sendable = sendable; - if (inst.liveWindowFactory) { - comp.builder = inst.liveWindowFactory(); - } - comp.liveWindow = true; - comp.name = name; - comp.subsystem = subsystem; -} - void SendableRegistry::AddChild(Sendable* parent, Sendable* child) { auto& inst = GetInstance(); std::scoped_lock lock(inst.mutex); @@ -361,26 +302,6 @@ std::shared_ptr SendableRegistry::GetData(Sendable* sendable, return comp.data[handle]; } -void SendableRegistry::EnableLiveWindow(Sendable* sendable) { - auto& inst = GetInstance(); - std::scoped_lock lock(inst.mutex); - auto it = inst.componentMap.find(sendable); - if (it == inst.componentMap.end() || !inst.components[it->getSecond() - 1]) { - return; - } - inst.components[it->getSecond() - 1]->liveWindow = true; -} - -void SendableRegistry::DisableLiveWindow(Sendable* sendable) { - auto& inst = GetInstance(); - std::scoped_lock lock(inst.mutex); - auto it = inst.componentMap.find(sendable); - if (it == inst.componentMap.end() || !inst.components[it->getSecond() - 1]) { - return; - } - inst.components[it->getSecond() - 1]->liveWindow = false; -} - SendableRegistry::UID SendableRegistry::GetUniqueId(Sendable* sendable) { auto& inst = GetInstance(); std::scoped_lock lock(inst.mutex); @@ -430,25 +351,3 @@ void SendableRegistry::Update(UID sendableUid) { inst.components[sendableUid - 1]->builder->Update(); } } - -void SendableRegistry::ForeachLiveWindow( - int dataHandle, wpi::function_ref callback) { - auto& inst = GetInstance(); - assert(dataHandle >= 0); - std::scoped_lock lock(inst.mutex); - wpi::SmallVector components; - for (auto&& comp : inst.components) { - components.emplace_back(comp.get()); - } - for (auto comp : components) { - if (comp && comp->builder && comp->sendable && comp->liveWindow) { - if (static_cast(dataHandle) >= comp->data.size()) { - comp->data.resize(dataHandle + 1); - } - CallbackData cbdata{comp->sendable, comp->name, - comp->subsystem, comp->parent, - comp->data[dataHandle], *comp->builder}; - callback(cbdata); - } - } -} diff --git a/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h b/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h index 1913d7cc72f..5b7d29f409c 100644 --- a/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h +++ b/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h @@ -48,14 +48,6 @@ class SendableBuilder { */ virtual void SetActuator(bool value) = 0; - /** - * Set the function that should be called to set the Sendable into a safe - * state. This is called when entering and exiting Live Window mode. - * - * @param func function - */ - virtual void SetSafeState(std::function func) = 0; - /** * Add a boolean property. * diff --git a/wpiutil/src/main/native/include/wpi/sendable/SendableRegistry.h b/wpiutil/src/main/native/include/wpi/sendable/SendableRegistry.h index 37ed45fe192..324c7d286ad 100644 --- a/wpiutil/src/main/native/include/wpi/sendable/SendableRegistry.h +++ b/wpiutil/src/main/native/include/wpi/sendable/SendableRegistry.h @@ -4,13 +4,10 @@ #pragma once -#include #include #include #include -#include "wpi/function_ref.h" - namespace wpi { class Sendable; @@ -18,7 +15,7 @@ class SendableBuilder; /** * The SendableRegistry class is the public interface for registering sensors - * and actuators for use on dashboards and LiveWindow. + * and actuators for use on dashboards. */ class SendableRegistry final { public: @@ -32,14 +29,6 @@ class SendableRegistry final { */ static void EnsureInitialized(); - /** - * Sets the factory for LiveWindow builders. - * - * @param factory factory function - */ - static void SetLiveWindowBuilderFactory( - std::function()> factory); - /** * Adds an object to the registry. * @@ -80,47 +69,6 @@ class SendableRegistry final { static void Add(Sendable* sendable, std::string_view subsystem, std::string_view name); - /** - * Adds an object to the registry and LiveWindow. - * - * @param sendable object to add - * @param name component name - */ - static void AddLW(Sendable* sendable, std::string_view name); - - /** - * Adds an object to the registry and LiveWindow. - * - * @param sendable object to add - * @param moduleType A string that defines the module name in the label for - * the value - * @param channel The channel number the device is plugged into - */ - static void AddLW(Sendable* sendable, std::string_view moduleType, - int channel); - - /** - * Adds an object to the registry and LiveWindow. - * - * @param sendable object to add - * @param moduleType A string that defines the module name in the label for - * the value - * @param moduleNumber The number of the particular module type - * @param channel The channel number the device is plugged into - */ - static void AddLW(Sendable* sendable, std::string_view moduleType, - int moduleNumber, int channel); - - /** - * Adds an object to the registry and LiveWindow. - * - * @param sendable object to add - * @param subsystem subsystem name - * @param name component name - */ - static void AddLW(Sendable* sendable, std::string_view subsystem, - std::string_view name); - /** * Adds a child object to an object. Adds the child object to the registry * if it's not already present. @@ -255,20 +203,6 @@ class SendableRegistry final { */ static std::shared_ptr GetData(Sendable* sendable, int handle); - /** - * Enables LiveWindow for an object. - * - * @param sendable object - */ - static void EnableLiveWindow(Sendable* sendable); - - /** - * Disables LiveWindow for an object. - * - * @param sendable object - */ - static void DisableLiveWindow(Sendable* sendable); - /** * Get unique id for an object. Since objects can move, use this instead * of storing Sendable* directly if ownership is in question. @@ -301,39 +235,6 @@ class SendableRegistry final { * @param sendableUid sendable unique id */ static void Update(UID sendableUid); - - /** - * Data passed to ForeachLiveWindow() callback function - */ - struct CallbackData { - CallbackData(Sendable* sendable_, std::string_view name_, - std::string_view subsystem_, wpi::Sendable* parent_, - std::shared_ptr& data_, SendableBuilder& builder_) - : sendable(sendable_), - name(name_), - subsystem(subsystem_), - parent(parent_), - data(data_), - builder(builder_) {} - - Sendable* sendable; - std::string_view name; - std::string_view subsystem; - Sendable* parent; - std::shared_ptr& data; - SendableBuilder& builder; - }; - - /** - * Iterates over LiveWindow-enabled objects in the registry. - * It is *not* safe to call other SendableRegistry functions from the - * callback (this will likely deadlock). - * - * @param dataHandle data handle to get data pointer passed to callback - * @param callback function to call for each object - */ - static void ForeachLiveWindow( - int dataHandle, wpi::function_ref callback); }; } // namespace wpi