diff --git a/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp b/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp index 71407da5a3..fca2d4c8b3 100644 --- a/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp +++ b/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,6 +10,7 @@ #include #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -22,7 +23,8 @@ ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress) HAL_Report(HALUsageReporting::kResourceType_ADXL345, HALUsageReporting::kADXL345_I2C, 0); - SetName("ADXL345_I2C", port); + + SendableRegistry::GetInstance().AddLW(this, "ADXL345_I2C", port); } void ADXL345_I2C::SetRange(Range range) { diff --git a/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp b/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp index 738bc3e5ab..28601e95d4 100644 --- a/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp +++ b/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,6 +10,7 @@ #include #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -32,7 +33,7 @@ ADXL345_SPI::ADXL345_SPI(SPI::Port port, ADXL345_SPI::Range range) HAL_Report(HALUsageReporting::kResourceType_ADXL345, HALUsageReporting::kADXL345_SPI); - SetName("ADXL345_SPI", port); + SendableRegistry::GetInstance().AddLW(this, "ADXL345_SPI", port); } void ADXL345_SPI::SetRange(Range range) { diff --git a/wpilibc/src/main/native/cpp/ADXL362.cpp b/wpilibc/src/main/native/cpp/ADXL362.cpp index d709ae41c0..26d7a693cf 100644 --- a/wpilibc/src/main/native/cpp/ADXL362.cpp +++ b/wpilibc/src/main/native/cpp/ADXL362.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,6 +11,7 @@ #include "frc/DriverStation.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -62,7 +63,7 @@ ADXL362::ADXL362(SPI::Port port, Range range) : m_spi(port) { HAL_Report(HALUsageReporting::kResourceType_ADXL362, port); - SetName("ADXL362", port); + SendableRegistry::GetInstance().AddLW(this, "ADXL362", port); } void ADXL362::SetRange(Range range) { diff --git a/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp b/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp index 71a350b14b..51ea031c99 100644 --- a/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp +++ b/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp @@ -11,6 +11,7 @@ #include "frc/DriverStation.h" #include "frc/Timer.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -49,7 +50,8 @@ ADXRS450_Gyro::ADXRS450_Gyro(SPI::Port port) : m_spi(port) { Calibrate(); HAL_Report(HALUsageReporting::kResourceType_ADXRS450, port); - SetName("ADXRS450_Gyro", port); + + SendableRegistry::GetInstance().AddLW(this, "ADXRS450_Gyro", port); } static bool CalcParity(int v) { diff --git a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp index 3ae8e482bb..4436bcf746 100644 --- a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp +++ b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,12 +11,13 @@ #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; AnalogAccelerometer::AnalogAccelerometer(int channel) : AnalogAccelerometer(std::make_shared(channel)) { - AddChild(m_analogInput); + SendableRegistry::GetInstance().AddChild(this, m_analogInput.get()); } AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel) @@ -58,5 +59,7 @@ void AnalogAccelerometer::InitSendable(SendableBuilder& builder) { void AnalogAccelerometer::InitAccelerometer() { HAL_Report(HALUsageReporting::kResourceType_Accelerometer, m_analogInput->GetChannel()); - SetName("Accelerometer", m_analogInput->GetChannel()); + + SendableRegistry::GetInstance().AddLW(this, "Accelerometer", + m_analogInput->GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/AnalogGyro.cpp b/wpilibc/src/main/native/cpp/AnalogGyro.cpp index 1c356b3cfa..36cde8a13b 100644 --- a/wpilibc/src/main/native/cpp/AnalogGyro.cpp +++ b/wpilibc/src/main/native/cpp/AnalogGyro.cpp @@ -17,12 +17,13 @@ #include "frc/AnalogInput.h" #include "frc/Timer.h" #include "frc/WPIErrors.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; AnalogGyro::AnalogGyro(int channel) : AnalogGyro(std::make_shared(channel)) { - AddChild(m_analog); + SendableRegistry::GetInstance().AddChild(this, m_analog.get()); } AnalogGyro::AnalogGyro(AnalogInput* channel) @@ -41,7 +42,7 @@ AnalogGyro::AnalogGyro(std::shared_ptr channel) AnalogGyro::AnalogGyro(int channel, int center, double offset) : AnalogGyro(std::make_shared(channel), center, offset) { - AddChild(m_analog); + SendableRegistry::GetInstance().AddChild(this, m_analog.get()); } AnalogGyro::AnalogGyro(std::shared_ptr channel, int center, @@ -148,7 +149,9 @@ void AnalogGyro::InitGyro() { } HAL_Report(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel()); - SetName("AnalogGyro", m_analog->GetChannel()); + + SendableRegistry::GetInstance().AddLW(this, "AnalogGyro", + m_analog->GetChannel()); } void AnalogGyro::Calibrate() { diff --git a/wpilibc/src/main/native/cpp/AnalogInput.cpp b/wpilibc/src/main/native/cpp/AnalogInput.cpp index 0945e5fa70..89c14dc331 100644 --- a/wpilibc/src/main/native/cpp/AnalogInput.cpp +++ b/wpilibc/src/main/native/cpp/AnalogInput.cpp @@ -18,6 +18,7 @@ #include "frc/Timer.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -42,7 +43,8 @@ AnalogInput::AnalogInput(int channel) { } HAL_Report(HALUsageReporting::kResourceType_AnalogChannel, channel); - SetName("AnalogInput", channel); + + SendableRegistry::GetInstance().AddLW(this, "AnalogInput", channel); } AnalogInput::~AnalogInput() { HAL_FreeAnalogInputPort(m_port); } diff --git a/wpilibc/src/main/native/cpp/AnalogOutput.cpp b/wpilibc/src/main/native/cpp/AnalogOutput.cpp index 5988d2084a..5e56efca94 100644 --- a/wpilibc/src/main/native/cpp/AnalogOutput.cpp +++ b/wpilibc/src/main/native/cpp/AnalogOutput.cpp @@ -16,6 +16,7 @@ #include "frc/SensorUtil.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -42,7 +43,7 @@ AnalogOutput::AnalogOutput(int channel) { } HAL_Report(HALUsageReporting::kResourceType_AnalogOutput, m_channel); - SetName("AnalogOutput", m_channel); + SendableRegistry::GetInstance().AddLW(this, "AnalogOutput", m_channel); } AnalogOutput::~AnalogOutput() { HAL_FreeAnalogOutputPort(m_port); } diff --git a/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp b/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp index 6c42ff9ebb..b650ec7132 100644 --- a/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp +++ b/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,26 +9,29 @@ #include "frc/RobotController.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange, double offset) - : m_analog_input(std::make_shared(channel)), - m_fullRange(fullRange), - m_offset(offset) { - AddChild(m_analog_input); + : AnalogPotentiometer(std::make_shared(channel), fullRange, + offset) { + SendableRegistry::GetInstance().AddChild(this, m_analog_input.get()); } AnalogPotentiometer::AnalogPotentiometer(AnalogInput* input, double fullRange, double offset) - : m_analog_input(input, NullDeleter()), - m_fullRange(fullRange), - m_offset(offset) {} + : AnalogPotentiometer( + std::shared_ptr(input, NullDeleter()), + fullRange, offset) {} AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr input, double fullRange, double offset) - : m_analog_input(input), m_fullRange(fullRange), m_offset(offset) {} + : m_analog_input(input), m_fullRange(fullRange), m_offset(offset) { + SendableRegistry::GetInstance().AddLW(this, "AnalogPotentiometer", + m_analog_input->GetChannel()); +} double AnalogPotentiometer::Get() const { return (m_analog_input->GetVoltage() / RobotController::GetVoltage5V()) * diff --git a/wpilibc/src/main/native/cpp/AnalogTrigger.cpp b/wpilibc/src/main/native/cpp/AnalogTrigger.cpp index 65a975887a..60ce04a53c 100644 --- a/wpilibc/src/main/native/cpp/AnalogTrigger.cpp +++ b/wpilibc/src/main/native/cpp/AnalogTrigger.cpp @@ -13,13 +13,14 @@ #include "frc/AnalogInput.h" #include "frc/WPIErrors.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; AnalogTrigger::AnalogTrigger(int channel) : AnalogTrigger(new AnalogInput(channel)) { m_ownsAnalog = true; - AddChild(m_analogInput); + SendableRegistry::GetInstance().AddChild(this, m_analogInput); } AnalogTrigger::AnalogTrigger(AnalogInput* input) { @@ -36,7 +37,8 @@ AnalogTrigger::AnalogTrigger(AnalogInput* input) { m_index = index; HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, input->m_channel); - SetName("AnalogTrigger", input->GetChannel()); + SendableRegistry::GetInstance().AddLW(this, "AnalogTrigger", + input->GetChannel()); } AnalogTrigger::~AnalogTrigger() { @@ -50,7 +52,7 @@ AnalogTrigger::~AnalogTrigger() { AnalogTrigger::AnalogTrigger(AnalogTrigger&& rhs) : ErrorBase(std::move(rhs)), - SendableBase(std::move(rhs)), + SendableHelper(std::move(rhs)), m_index(std::move(rhs.m_index)), m_trigger(std::move(rhs.m_trigger)) { std::swap(m_analogInput, rhs.m_analogInput); @@ -59,7 +61,7 @@ AnalogTrigger::AnalogTrigger(AnalogTrigger&& rhs) AnalogTrigger& AnalogTrigger::operator=(AnalogTrigger&& rhs) { ErrorBase::operator=(std::move(rhs)); - SendableBase::operator=(std::move(rhs)); + SendableHelper::operator=(std::move(rhs)); m_index = std::move(rhs.m_index); m_trigger = std::move(rhs.m_trigger); diff --git a/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp b/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp index 8452e38c4a..71c8e89ebd 100644 --- a/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp +++ b/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,6 +12,7 @@ #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -20,7 +21,7 @@ BuiltInAccelerometer::BuiltInAccelerometer(Range range) { HAL_Report(HALUsageReporting::kResourceType_Accelerometer, 0, 0, "Built-in accelerometer"); - SetName("BuiltInAccel", 0); + SendableRegistry::GetInstance().AddLW(this, "BuiltInAccel"); } void BuiltInAccelerometer::SetRange(Range range) { diff --git a/wpilibc/src/main/native/cpp/Compressor.cpp b/wpilibc/src/main/native/cpp/Compressor.cpp index 48e1ed6fbd..10d75f11da 100644 --- a/wpilibc/src/main/native/cpp/Compressor.cpp +++ b/wpilibc/src/main/native/cpp/Compressor.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -14,6 +14,7 @@ #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -28,7 +29,7 @@ Compressor::Compressor(int pcmID) : m_module(pcmID) { SetClosedLoopControl(true); HAL_Report(HALUsageReporting::kResourceType_Compressor, pcmID); - SetName("Compressor", pcmID); + SendableRegistry::GetInstance().AddLW(this, "Compressor", pcmID); } void Compressor::Start() { diff --git a/wpilibc/src/main/native/cpp/Counter.cpp b/wpilibc/src/main/native/cpp/Counter.cpp index e7bf035090..1ef40fd7ad 100644 --- a/wpilibc/src/main/native/cpp/Counter.cpp +++ b/wpilibc/src/main/native/cpp/Counter.cpp @@ -15,6 +15,7 @@ #include "frc/DigitalInput.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -26,7 +27,7 @@ Counter::Counter(Mode mode) { SetMaxPeriod(.5); HAL_Report(HALUsageReporting::kResourceType_Counter, m_index, mode); - SetName("Counter", m_index); + SendableRegistry::GetInstance().AddLW(this, "Counter", m_index); } Counter::Counter(int channel) : Counter(kTwoPulse) { @@ -95,7 +96,7 @@ Counter::~Counter() { void Counter::SetUpSource(int channel) { if (StatusIsFatal()) return; SetUpSource(std::make_shared(channel)); - AddChild(m_upSource); + SendableRegistry::GetInstance().AddChild(this, m_upSource.get()); } void Counter::SetUpSource(AnalogTrigger* analogTrigger, @@ -159,7 +160,7 @@ void Counter::ClearUpSource() { void Counter::SetDownSource(int channel) { if (StatusIsFatal()) return; SetDownSource(std::make_shared(channel)); - AddChild(m_downSource); + SendableRegistry::GetInstance().AddChild(this, m_downSource.get()); } void Counter::SetDownSource(AnalogTrigger* analogTrigger, diff --git a/wpilibc/src/main/native/cpp/DMC60.cpp b/wpilibc/src/main/native/cpp/DMC60.cpp index 7dc2d8d7db..d61bd400f4 100644 --- a/wpilibc/src/main/native/cpp/DMC60.cpp +++ b/wpilibc/src/main/native/cpp/DMC60.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,8 @@ #include +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; DMC60::DMC60(int channel) : PWMSpeedController(channel) { @@ -32,5 +34,5 @@ DMC60::DMC60(int channel) : PWMSpeedController(channel) { SetZeroLatch(); HAL_Report(HALUsageReporting::kResourceType_DigilentDMC60, GetChannel()); - SetName("DMC60", GetChannel()); + SendableRegistry::GetInstance().SetName(this, "DMC60", GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp b/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp index 811fab24d9..9e92da8afa 100644 --- a/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp +++ b/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp @@ -20,6 +20,7 @@ #include "frc/SensorUtil.h" #include "frc/Utility.h" #include "frc/WPIErrors.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -38,7 +39,8 @@ DigitalGlitchFilter::DigitalGlitchFilter() { HAL_Report(HALUsageReporting::kResourceType_DigitalGlitchFilter, m_channelIndex); - SetName("DigitalGlitchFilter", m_channelIndex); + SendableRegistry::GetInstance().AddLW(this, "DigitalGlitchFilter", + m_channelIndex); } DigitalGlitchFilter::~DigitalGlitchFilter() { @@ -49,13 +51,13 @@ DigitalGlitchFilter::~DigitalGlitchFilter() { } DigitalGlitchFilter::DigitalGlitchFilter(DigitalGlitchFilter&& rhs) - : ErrorBase(std::move(rhs)), SendableBase(std::move(rhs)) { + : ErrorBase(std::move(rhs)), SendableHelper(std::move(rhs)) { std::swap(m_channelIndex, rhs.m_channelIndex); } DigitalGlitchFilter& DigitalGlitchFilter::operator=(DigitalGlitchFilter&& rhs) { ErrorBase::operator=(std::move(rhs)); - SendableBase::operator=(std::move(rhs)); + SendableHelper::operator=(std::move(rhs)); std::swap(m_channelIndex, rhs.m_channelIndex); diff --git a/wpilibc/src/main/native/cpp/DigitalInput.cpp b/wpilibc/src/main/native/cpp/DigitalInput.cpp index 248bdd5232..75ea3390e5 100644 --- a/wpilibc/src/main/native/cpp/DigitalInput.cpp +++ b/wpilibc/src/main/native/cpp/DigitalInput.cpp @@ -17,6 +17,7 @@ #include "frc/SensorUtil.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -40,7 +41,7 @@ DigitalInput::DigitalInput(int channel) { } HAL_Report(HALUsageReporting::kResourceType_DigitalInput, channel); - SetName("DigitalInput", channel); + SendableRegistry::GetInstance().AddLW(this, "DigitalInput", channel); } DigitalInput::~DigitalInput() { diff --git a/wpilibc/src/main/native/cpp/DigitalOutput.cpp b/wpilibc/src/main/native/cpp/DigitalOutput.cpp index f2224c7b7f..53697c1cdc 100644 --- a/wpilibc/src/main/native/cpp/DigitalOutput.cpp +++ b/wpilibc/src/main/native/cpp/DigitalOutput.cpp @@ -17,6 +17,7 @@ #include "frc/SensorUtil.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -41,7 +42,7 @@ DigitalOutput::DigitalOutput(int channel) { } HAL_Report(HALUsageReporting::kResourceType_DigitalOutput, channel); - SetName("DigitalOutput", channel); + SendableRegistry::GetInstance().AddLW(this, "DigitalOutput", channel); } DigitalOutput::~DigitalOutput() { diff --git a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp index 0f0a6941d2..0b35ff5322 100644 --- a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp +++ b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp @@ -16,6 +16,7 @@ #include "frc/SensorUtil.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -75,7 +76,9 @@ DoubleSolenoid::DoubleSolenoid(int moduleNumber, int forwardChannel, m_moduleNumber); HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel, m_moduleNumber); - SetName("DoubleSolenoid", m_moduleNumber, m_forwardChannel); + + SendableRegistry::GetInstance().AddLW(this, "DoubleSolenoid", m_moduleNumber, + m_forwardChannel); } DoubleSolenoid::~DoubleSolenoid() { diff --git a/wpilibc/src/main/native/cpp/Encoder.cpp b/wpilibc/src/main/native/cpp/Encoder.cpp index 1c4d02f530..adf6014b29 100644 --- a/wpilibc/src/main/native/cpp/Encoder.cpp +++ b/wpilibc/src/main/native/cpp/Encoder.cpp @@ -16,6 +16,7 @@ #include "frc/DigitalInput.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -24,8 +25,9 @@ Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection, m_aSource = std::make_shared(aChannel); m_bSource = std::make_shared(bChannel); InitEncoder(reverseDirection, encodingType); - AddChild(m_aSource); - AddChild(m_bSource); + auto& registry = SendableRegistry::GetInstance(); + registry.AddChild(this, m_aSource.get()); + registry.AddChild(this, m_bSource.get()); } Encoder::Encoder(DigitalSource* aSource, DigitalSource* bSource, @@ -201,7 +203,7 @@ double Encoder::PIDGet() { void Encoder::SetIndexSource(int channel, Encoder::IndexingType type) { // Force digital input if just given an index m_indexSource = std::make_shared(channel); - AddChild(m_indexSource); + SendableRegistry::GetInstance().AddChild(this, m_indexSource.get()); SetIndexSource(*m_indexSource.get(), type); } @@ -250,7 +252,8 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) { HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex(), encodingType); - SetName("Encoder", m_aSource->GetChannel()); + SendableRegistry::GetInstance().AddLW(this, "Encoder", + m_aSource->GetChannel()); } double Encoder::DecodingScaleFactor() const { diff --git a/wpilibc/src/main/native/cpp/GearTooth.cpp b/wpilibc/src/main/native/cpp/GearTooth.cpp index fba5a24e05..5fb5021160 100644 --- a/wpilibc/src/main/native/cpp/GearTooth.cpp +++ b/wpilibc/src/main/native/cpp/GearTooth.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -8,6 +8,7 @@ #include "frc/GearTooth.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -15,20 +16,22 @@ constexpr double GearTooth::kGearToothThreshold; GearTooth::GearTooth(int channel, bool directionSensitive) : Counter(channel) { EnableDirectionSensing(directionSensitive); - SetName("GearTooth", channel); + SendableRegistry::GetInstance().SetName(this, "GearTooth", channel); } GearTooth::GearTooth(DigitalSource* source, bool directionSensitive) : Counter(source) { EnableDirectionSensing(directionSensitive); - SetName("GearTooth", source->GetChannel()); + SendableRegistry::GetInstance().SetName(this, "GearTooth", + source->GetChannel()); } GearTooth::GearTooth(std::shared_ptr source, bool directionSensitive) : Counter(source) { EnableDirectionSensing(directionSensitive); - SetName("GearTooth", source->GetChannel()); + SendableRegistry::GetInstance().SetName(this, "GearTooth", + source->GetChannel()); } void GearTooth::EnableDirectionSensing(bool directionSensitive) { diff --git a/wpilibc/src/main/native/cpp/Jaguar.cpp b/wpilibc/src/main/native/cpp/Jaguar.cpp index 7bde6ba215..487d4897bb 100644 --- a/wpilibc/src/main/native/cpp/Jaguar.cpp +++ b/wpilibc/src/main/native/cpp/Jaguar.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,8 @@ #include +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; Jaguar::Jaguar(int channel) : PWMSpeedController(channel) { @@ -26,5 +28,5 @@ Jaguar::Jaguar(int channel) : PWMSpeedController(channel) { SetZeroLatch(); HAL_Report(HALUsageReporting::kResourceType_Jaguar, GetChannel()); - SetName("Jaguar", GetChannel()); + SendableRegistry::GetInstance().SetName(this, "Jaguar", GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/NidecBrushless.cpp b/wpilibc/src/main/native/cpp/NidecBrushless.cpp index 0ccc7c7814..90ce43e713 100644 --- a/wpilibc/src/main/native/cpp/NidecBrushless.cpp +++ b/wpilibc/src/main/native/cpp/NidecBrushless.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,13 +10,15 @@ #include #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel) : m_dio(dioChannel), m_pwm(pwmChannel) { - AddChild(&m_dio); - AddChild(&m_pwm); + auto& registry = SendableRegistry::GetInstance(); + registry.AddChild(this, &m_dio); + registry.AddChild(this, &m_pwm); SetExpiration(0.0); SetSafetyEnabled(false); @@ -25,7 +27,7 @@ NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel) m_dio.EnablePWM(0.5); HAL_Report(HALUsageReporting::kResourceType_NidecBrushless, pwmChannel); - SetName("Nidec Brushless", pwmChannel); + registry.AddLW(this, "Nidec Brushless", pwmChannel); } void NidecBrushless::Set(double speed) { diff --git a/wpilibc/src/main/native/cpp/PIDBase.cpp b/wpilibc/src/main/native/cpp/PIDBase.cpp index e84d796e82..a2efe0f23c 100644 --- a/wpilibc/src/main/native/cpp/PIDBase.cpp +++ b/wpilibc/src/main/native/cpp/PIDBase.cpp @@ -14,6 +14,7 @@ #include "frc/PIDOutput.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -27,8 +28,7 @@ PIDBase::PIDBase(double Kp, double Ki, double Kd, PIDSource& source, : PIDBase(Kp, Ki, Kd, 0.0, source, output) {} PIDBase::PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource& source, - PIDOutput& output) - : SendableBase(false) { + PIDOutput& output) { m_P = Kp; m_I = Ki; m_D = Kd; @@ -44,7 +44,7 @@ PIDBase::PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource& source, static int instances = 0; instances++; HAL_Report(HALUsageReporting::kResourceType_PIDController, instances); - SetName("PIDController", instances); + SendableRegistry::GetInstance().Add(this, "PIDController", instances); } double PIDBase::Get() const { diff --git a/wpilibc/src/main/native/cpp/PWM.cpp b/wpilibc/src/main/native/cpp/PWM.cpp index e0e578e3ef..c6b398f5cc 100644 --- a/wpilibc/src/main/native/cpp/PWM.cpp +++ b/wpilibc/src/main/native/cpp/PWM.cpp @@ -17,6 +17,7 @@ #include "frc/Utility.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -46,7 +47,7 @@ PWM::PWM(int channel) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); HAL_Report(HALUsageReporting::kResourceType_PWM, channel); - SetName("PWM", channel); + SendableRegistry::GetInstance().AddLW(this, "PWM", channel); SetSafetyEnabled(false); } diff --git a/wpilibc/src/main/native/cpp/PWMSparkMax.cpp b/wpilibc/src/main/native/cpp/PWMSparkMax.cpp index d441315adb..d8d3b2a43b 100644 --- a/wpilibc/src/main/native/cpp/PWMSparkMax.cpp +++ b/wpilibc/src/main/native/cpp/PWMSparkMax.cpp @@ -9,6 +9,8 @@ #include +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; PWMSparkMax::PWMSparkMax(int channel) : PWMSpeedController(channel) { @@ -26,5 +28,5 @@ PWMSparkMax::PWMSparkMax(int channel) : PWMSpeedController(channel) { SetZeroLatch(); HAL_Report(HALUsageReporting::kResourceType_RevSparkMaxPWM, GetChannel()); - SetName("PWMSparkMax", GetChannel()); + SendableRegistry::GetInstance().SetName(this, "PWMSparkMax", GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/PWMTalonSRX.cpp b/wpilibc/src/main/native/cpp/PWMTalonSRX.cpp index ccb50b6128..0bbc5b9ced 100644 --- a/wpilibc/src/main/native/cpp/PWMTalonSRX.cpp +++ b/wpilibc/src/main/native/cpp/PWMTalonSRX.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,8 @@ #include +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; PWMTalonSRX::PWMTalonSRX(int channel) : PWMSpeedController(channel) { @@ -30,5 +32,5 @@ PWMTalonSRX::PWMTalonSRX(int channel) : PWMSpeedController(channel) { SetZeroLatch(); HAL_Report(HALUsageReporting::kResourceType_PWMTalonSRX, GetChannel()); - SetName("PWMTalonSRX", GetChannel()); + SendableRegistry::GetInstance().SetName(this, "PWMTalonSRX", GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/PWMVictorSPX.cpp b/wpilibc/src/main/native/cpp/PWMVictorSPX.cpp index b4f1fd27e5..122d2197bf 100644 --- a/wpilibc/src/main/native/cpp/PWMVictorSPX.cpp +++ b/wpilibc/src/main/native/cpp/PWMVictorSPX.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,8 @@ #include +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; PWMVictorSPX::PWMVictorSPX(int channel) : PWMSpeedController(channel) { @@ -30,5 +32,5 @@ PWMVictorSPX::PWMVictorSPX(int channel) : PWMSpeedController(channel) { SetZeroLatch(); HAL_Report(HALUsageReporting::kResourceType_PWMVictorSPX, GetChannel()); - SetName("PWMVictorSPX", GetChannel()); + SendableRegistry::GetInstance().SetName(this, "PWMVictorSPX", GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp b/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp index 8872028e1d..b3297ea986 100644 --- a/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp +++ b/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -16,6 +16,7 @@ #include "frc/SensorUtil.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -34,7 +35,7 @@ PowerDistributionPanel::PowerDistributionPanel(int module) { } HAL_Report(HALUsageReporting::kResourceType_PDP, module); - SetName("PowerDistributionPanel", module); + SendableRegistry::GetInstance().AddLW(this, "PowerDistributionPanel", module); } double PowerDistributionPanel::GetVoltage() const { diff --git a/wpilibc/src/main/native/cpp/Relay.cpp b/wpilibc/src/main/native/cpp/Relay.cpp index 970a5e150a..3a3e7727e1 100644 --- a/wpilibc/src/main/native/cpp/Relay.cpp +++ b/wpilibc/src/main/native/cpp/Relay.cpp @@ -17,6 +17,7 @@ #include "frc/SensorUtil.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -76,7 +77,7 @@ Relay::Relay(int channel, Relay::Direction direction) } } - SetName("Relay", m_channel); + SendableRegistry::GetInstance().AddLW(this, "Relay", m_channel); } Relay::~Relay() { diff --git a/wpilibc/src/main/native/cpp/SD540.cpp b/wpilibc/src/main/native/cpp/SD540.cpp index 977ae7bbd7..93733b2fbf 100644 --- a/wpilibc/src/main/native/cpp/SD540.cpp +++ b/wpilibc/src/main/native/cpp/SD540.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,8 @@ #include +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; SD540::SD540(int channel) : PWMSpeedController(channel) { @@ -31,5 +33,5 @@ SD540::SD540(int channel) : PWMSpeedController(channel) { SetZeroLatch(); HAL_Report(HALUsageReporting::kResourceType_MindsensorsSD540, GetChannel()); - SetName("SD540", GetChannel()); + SendableRegistry::GetInstance().SetName(this, "SD540", GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/Servo.cpp b/wpilibc/src/main/native/cpp/Servo.cpp index b4c9eb5ce1..09e482b260 100644 --- a/wpilibc/src/main/native/cpp/Servo.cpp +++ b/wpilibc/src/main/native/cpp/Servo.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,6 +10,7 @@ #include #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -27,7 +28,7 @@ Servo::Servo(int channel) : PWM(channel) { SetPeriodMultiplier(kPeriodMultiplier_4X); HAL_Report(HALUsageReporting::kResourceType_Servo, channel); - SetName("Servo", channel); + SendableRegistry::GetInstance().SetName(this, "Servo", channel); } void Servo::Set(double value) { SetPosition(value); } diff --git a/wpilibc/src/main/native/cpp/Solenoid.cpp b/wpilibc/src/main/native/cpp/Solenoid.cpp index 7bc2f4e457..c860c44106 100644 --- a/wpilibc/src/main/native/cpp/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/Solenoid.cpp @@ -16,6 +16,7 @@ #include "frc/SensorUtil.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -47,7 +48,8 @@ Solenoid::Solenoid(int moduleNumber, int channel) HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_channel, m_moduleNumber); - SetName("Solenoid", m_moduleNumber, m_channel); + SendableRegistry::GetInstance().AddLW(this, "Solenoid", m_moduleNumber, + m_channel); } Solenoid::~Solenoid() { HAL_FreeSolenoidPort(m_solenoidHandle); } diff --git a/wpilibc/src/main/native/cpp/Spark.cpp b/wpilibc/src/main/native/cpp/Spark.cpp index fcfcb961a2..18f8ee65d3 100644 --- a/wpilibc/src/main/native/cpp/Spark.cpp +++ b/wpilibc/src/main/native/cpp/Spark.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,8 @@ #include +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; Spark::Spark(int channel) : PWMSpeedController(channel) { @@ -31,5 +33,5 @@ Spark::Spark(int channel) : PWMSpeedController(channel) { SetZeroLatch(); HAL_Report(HALUsageReporting::kResourceType_RevSPARK, GetChannel()); - SetName("Spark", GetChannel()); + SendableRegistry::GetInstance().SetName(this, "Spark", GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/Talon.cpp b/wpilibc/src/main/native/cpp/Talon.cpp index 34f659ad74..8dc1928d08 100644 --- a/wpilibc/src/main/native/cpp/Talon.cpp +++ b/wpilibc/src/main/native/cpp/Talon.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,8 @@ #include +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; Talon::Talon(int channel) : PWMSpeedController(channel) { @@ -31,5 +33,5 @@ Talon::Talon(int channel) : PWMSpeedController(channel) { SetZeroLatch(); HAL_Report(HALUsageReporting::kResourceType_Talon, GetChannel()); - SetName("Talon", GetChannel()); + SendableRegistry::GetInstance().SetName(this, "Talon", GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/Ultrasonic.cpp b/wpilibc/src/main/native/cpp/Ultrasonic.cpp index ee4f5cc52d..3e106532f0 100644 --- a/wpilibc/src/main/native/cpp/Ultrasonic.cpp +++ b/wpilibc/src/main/native/cpp/Ultrasonic.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -16,6 +16,7 @@ #include "frc/Utility.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -31,8 +32,9 @@ Ultrasonic::Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units) m_counter(m_echoChannel) { m_units = units; Initialize(); - AddChild(m_pingChannel); - AddChild(m_echoChannel); + auto& registry = SendableRegistry::GetInstance(); + registry.AddChild(this, m_pingChannel.get()); + registry.AddChild(this, m_echoChannel.get()); } Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel, @@ -189,7 +191,8 @@ void Ultrasonic::Initialize() { static int instances = 0; instances++; HAL_Report(HALUsageReporting::kResourceType_Ultrasonic, instances); - SetName("Ultrasonic", m_echoChannel->GetChannel()); + SendableRegistry::GetInstance().AddLW(this, "Ultrasonic", + m_echoChannel->GetChannel()); } void Ultrasonic::UltrasonicChecker() { diff --git a/wpilibc/src/main/native/cpp/Victor.cpp b/wpilibc/src/main/native/cpp/Victor.cpp index 2c29ecea24..49dcd574cd 100644 --- a/wpilibc/src/main/native/cpp/Victor.cpp +++ b/wpilibc/src/main/native/cpp/Victor.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,8 @@ #include +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; Victor::Victor(int channel) : PWMSpeedController(channel) { @@ -32,5 +34,5 @@ Victor::Victor(int channel) : PWMSpeedController(channel) { SetZeroLatch(); HAL_Report(HALUsageReporting::kResourceType_Victor, GetChannel()); - SetName("Victor", GetChannel()); + SendableRegistry::GetInstance().SetName(this, "Victor", GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/VictorSP.cpp b/wpilibc/src/main/native/cpp/VictorSP.cpp index 5e2b6b9731..82e966f62e 100644 --- a/wpilibc/src/main/native/cpp/VictorSP.cpp +++ b/wpilibc/src/main/native/cpp/VictorSP.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,8 @@ #include +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; VictorSP::VictorSP(int channel) : PWMSpeedController(channel) { @@ -31,5 +33,5 @@ VictorSP::VictorSP(int channel) : PWMSpeedController(channel) { SetZeroLatch(); HAL_Report(HALUsageReporting::kResourceType_VictorSP, GetChannel()); - SetName("VictorSP", GetChannel()); + SendableRegistry::GetInstance().SetName(this, "VictorSP", GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/commands/Command.cpp b/wpilibc/src/main/native/cpp/commands/Command.cpp index ad7824a1b1..a7154c0b87 100644 --- a/wpilibc/src/main/native/cpp/commands/Command.cpp +++ b/wpilibc/src/main/native/cpp/commands/Command.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2011-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2011-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -16,6 +16,7 @@ #include "frc/commands/Scheduler.h" #include "frc/livewindow/LiveWindow.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -31,7 +32,7 @@ Command::Command(Subsystem& subsystem) : Command("", -1.0) { Requires(&subsystem); } -Command::Command(const wpi::Twine& name, double timeout) : SendableBase(false) { +Command::Command(const wpi::Twine& name, double timeout) { // We use -1.0 to indicate no timeout. if (timeout < 0.0 && timeout != -1.0) wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0"); @@ -41,9 +42,10 @@ Command::Command(const wpi::Twine& name, double timeout) : SendableBase(false) { // If name contains an empty string if (name.isTriviallyEmpty() || (name.isSingleStringRef() && name.getSingleStringRef().empty())) { - SetName("Command_" + wpi::Twine(typeid(*this).name())); + SendableRegistry::GetInstance().Add( + this, "Command_" + wpi::Twine(typeid(*this).name())); } else { - SetName(name); + SendableRegistry::GetInstance().Add(this, name); } } @@ -228,9 +230,27 @@ void Command::StartRunning() { void Command::StartTiming() { m_startTime = Timer::GetFPGATimestamp(); } +std::string Command::GetName() const { + return SendableRegistry::GetInstance().GetName(this); +} + +void Command::SetName(const wpi::Twine& name) { + SendableRegistry::GetInstance().SetName(this, name); +} + +std::string Command::GetSubsystem() const { + return SendableRegistry::GetInstance().GetSubsystem(this); +} + +void Command::SetSubsystem(const wpi::Twine& name) { + SendableRegistry::GetInstance().SetSubsystem(this, name); +} + void Command::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Command"); - builder.AddStringProperty(".name", [=]() { return GetName(); }, nullptr); + builder.AddStringProperty( + ".name", [=]() { return SendableRegistry::GetInstance().GetName(this); }, + nullptr); builder.AddBooleanProperty("running", [=]() { return IsRunning(); }, [=](bool value) { if (value) { diff --git a/wpilibc/src/main/native/cpp/commands/Scheduler.cpp b/wpilibc/src/main/native/cpp/commands/Scheduler.cpp index a51cfc8dd8..f406d74a27 100644 --- a/wpilibc/src/main/native/cpp/commands/Scheduler.cpp +++ b/wpilibc/src/main/native/cpp/commands/Scheduler.cpp @@ -21,6 +21,7 @@ #include "frc/commands/Command.h" #include "frc/commands/Subsystem.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -182,8 +183,9 @@ void Scheduler::InitSendable(SendableBuilder& builder) { if (m_impl->runningCommandsChanged) { m_impl->commandsBuf.resize(0); m_impl->idsBuf.resize(0); + auto& registry = SendableRegistry::GetInstance(); for (const auto& command : m_impl->commands) { - m_impl->commandsBuf.emplace_back(command->GetName()); + m_impl->commandsBuf.emplace_back(registry.GetName(command)); m_impl->idsBuf.emplace_back(command->GetID()); } nt::NetworkTableEntry(namesEntry).SetStringArray(m_impl->commandsBuf); @@ -195,7 +197,7 @@ void Scheduler::InitSendable(SendableBuilder& builder) { Scheduler::Scheduler() : m_impl(new Impl) { HAL_Report(HALUsageReporting::kResourceType_Command, HALUsageReporting::kCommand_Scheduler); - SetName("Scheduler"); + SendableRegistry::GetInstance().AddLW(this, "Scheduler"); } Scheduler::~Scheduler() {} diff --git a/wpilibc/src/main/native/cpp/commands/Subsystem.cpp b/wpilibc/src/main/native/cpp/commands/Subsystem.cpp index 308642f920..6e665ea7d8 100644 --- a/wpilibc/src/main/native/cpp/commands/Subsystem.cpp +++ b/wpilibc/src/main/native/cpp/commands/Subsystem.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2011-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2011-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,11 +12,12 @@ #include "frc/commands/Scheduler.h" #include "frc/livewindow/LiveWindow.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; Subsystem::Subsystem(const wpi::Twine& name) { - SetName(name, name); + SendableRegistry::GetInstance().AddLW(this, name, name); Scheduler::GetInstance()->RegisterSubsystem(this); } @@ -46,7 +47,7 @@ Command* Subsystem::GetDefaultCommand() { wpi::StringRef Subsystem::GetDefaultCommandName() { Command* defaultCommand = GetDefaultCommand(); if (defaultCommand) { - return defaultCommand->GetName(); + return SendableRegistry::GetInstance().GetName(defaultCommand); } else { return wpi::StringRef(); } @@ -62,7 +63,7 @@ Command* Subsystem::GetCurrentCommand() const { return m_currentCommand; } wpi::StringRef Subsystem::GetCurrentCommandName() const { Command* currentCommand = GetCurrentCommand(); if (currentCommand) { - return currentCommand->GetName(); + return SendableRegistry::GetInstance().GetName(currentCommand); } else { return wpi::StringRef(); } @@ -72,6 +73,22 @@ void Subsystem::Periodic() {} void Subsystem::InitDefaultCommand() {} +std::string Subsystem::GetName() const { + return SendableRegistry::GetInstance().GetName(this); +} + +void Subsystem::SetName(const wpi::Twine& name) { + SendableRegistry::GetInstance().SetName(this, name); +} + +std::string Subsystem::GetSubsystem() const { + return SendableRegistry::GetInstance().GetSubsystem(this); +} + +void Subsystem::SetSubsystem(const wpi::Twine& name) { + SendableRegistry::GetInstance().SetSubsystem(this, name); +} + void Subsystem::AddChild(const wpi::Twine& name, std::shared_ptr child) { AddChild(name, *child); @@ -82,8 +99,9 @@ void Subsystem::AddChild(const wpi::Twine& name, Sendable* child) { } void Subsystem::AddChild(const wpi::Twine& name, Sendable& child) { - child.SetName(GetSubsystem(), name); - LiveWindow::GetInstance()->Add(&child); + auto& registry = SendableRegistry::GetInstance(); + registry.AddLW(&child, registry.GetSubsystem(this), name); + registry.AddChild(this, &child); } void Subsystem::AddChild(std::shared_ptr child) { AddChild(*child); } @@ -91,8 +109,10 @@ void Subsystem::AddChild(std::shared_ptr child) { AddChild(*child); } void Subsystem::AddChild(Sendable* child) { AddChild(*child); } void Subsystem::AddChild(Sendable& child) { - child.SetSubsystem(GetSubsystem()); - LiveWindow::GetInstance()->Add(&child); + auto& registry = SendableRegistry::GetInstance(); + registry.SetSubsystem(&child, registry.GetSubsystem(this)); + registry.EnableLiveWindow(&child); + registry.AddChild(this, &child); } void Subsystem::ConfirmCommand() { diff --git a/wpilibc/src/main/native/cpp/controller/PIDController.cpp b/wpilibc/src/main/native/cpp/controller/PIDController.cpp index 374fa74f46..2202d93dae 100644 --- a/wpilibc/src/main/native/cpp/controller/PIDController.cpp +++ b/wpilibc/src/main/native/cpp/controller/PIDController.cpp @@ -13,16 +13,17 @@ #include #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc2; PIDController::PIDController(double Kp, double Ki, double Kd, units::second_t period) - : frc::SendableBase(false), m_Kp(Kp), m_Ki(Ki), m_Kd(Kd), m_period(period) { + : m_Kp(Kp), m_Ki(Ki), m_Kd(Kd), m_period(period) { static int instances = 0; instances++; HAL_Report(HALUsageReporting::kResourceType_PIDController, instances); - SetName("PIDController", instances); + frc::SendableRegistry::GetInstance().Add(this, "PIDController", instances); } void PIDController::SetP(double Kp) { m_Kp = Kp; } diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index eab55a8444..c41e395264 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -14,17 +14,19 @@ #include "frc/SpeedController.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; DifferentialDrive::DifferentialDrive(SpeedController& leftMotor, SpeedController& rightMotor) : m_leftMotor(leftMotor), m_rightMotor(rightMotor) { - AddChild(&m_leftMotor); - AddChild(&m_rightMotor); + auto& registry = SendableRegistry::GetInstance(); + registry.AddChild(this, &m_leftMotor); + registry.AddChild(this, &m_rightMotor); static int instances = 0; ++instances; - SetName("DifferentialDrive", instances); + registry.AddLW(this, "DifferentialDrive", instances); } void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation, diff --git a/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp b/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp index 736683bbdc..60af5afd07 100644 --- a/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp @@ -15,6 +15,7 @@ #include "frc/SpeedController.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -35,12 +36,13 @@ KilloughDrive::KilloughDrive(SpeedController& leftMotor, std::sin(rightMotorAngle * (wpi::math::pi / 180.0))}; m_backVec = {std::cos(backMotorAngle * (wpi::math::pi / 180.0)), std::sin(backMotorAngle * (wpi::math::pi / 180.0))}; - AddChild(&m_leftMotor); - AddChild(&m_rightMotor); - AddChild(&m_backMotor); + auto& registry = SendableRegistry::GetInstance(); + registry.AddChild(this, &m_leftMotor); + registry.AddChild(this, &m_rightMotor); + registry.AddChild(this, &m_backMotor); static int instances = 0; ++instances; - SetName("KilloughDrive", instances); + registry.AddLW(this, "KilloughDrive", instances); } void KilloughDrive::DriveCartesian(double ySpeed, double xSpeed, diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index 41ca2eefd3..55929c5815 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -16,6 +16,7 @@ #include "frc/SpeedController.h" #include "frc/drive/Vector2d.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -27,13 +28,14 @@ MecanumDrive::MecanumDrive(SpeedController& frontLeftMotor, m_rearLeftMotor(rearLeftMotor), m_frontRightMotor(frontRightMotor), m_rearRightMotor(rearRightMotor) { - AddChild(&m_frontLeftMotor); - AddChild(&m_rearLeftMotor); - AddChild(&m_frontRightMotor); - AddChild(&m_rearRightMotor); + auto& registry = SendableRegistry::GetInstance(); + registry.AddChild(this, &m_frontLeftMotor); + registry.AddChild(this, &m_rearLeftMotor); + registry.AddChild(this, &m_frontRightMotor); + registry.AddChild(this, &m_rearRightMotor); static int instances = 0; ++instances; - SetName("MecanumDrive", instances); + registry.AddLW(this, "MecanumDrive", instances); } void MecanumDrive::DriveCartesian(double ySpeed, double xSpeed, diff --git a/wpilibc/src/main/native/cpp/frc2/command/Command.cpp b/wpilibc/src/main/native/cpp/frc2/command/Command.cpp index b2be43bc93..20f1b2047b 100644 --- a/wpilibc/src/main/native/cpp/frc2/command/Command.cpp +++ b/wpilibc/src/main/native/cpp/frc2/command/Command.cpp @@ -24,6 +24,14 @@ using namespace frc2; Command::~Command() { CommandScheduler::GetInstance().Cancel(this); } +Command::Command(const Command& rhs) : ErrorBase(rhs) {} + +Command& Command::operator=(const Command& rhs) { + ErrorBase::operator=(rhs); + m_isGrouped = false; + return *this; +} + void Command::Initialize() {} void Command::Execute() {} void Command::End(bool interrupted) {} diff --git a/wpilibc/src/main/native/cpp/frc2/command/CommandBase.cpp b/wpilibc/src/main/native/cpp/frc2/command/CommandBase.cpp index c3cf024ca9..aeba26bd58 100644 --- a/wpilibc/src/main/native/cpp/frc2/command/CommandBase.cpp +++ b/wpilibc/src/main/native/cpp/frc2/command/CommandBase.cpp @@ -8,20 +8,14 @@ #include "frc2/command/CommandBase.h" #include +#include #include #include using namespace frc2; CommandBase::CommandBase() { - m_name = Command::GetName(); - m_subsystem = "Unknown"; -} - -CommandBase::CommandBase(const CommandBase& other) : Sendable{}, Command{} { - m_name = other.m_name; - m_subsystem = other.m_subsystem; - m_requirements = other.m_requirements; + frc::SendableRegistry::GetInstance().AddLW(this, GetTypeName(*this)); } void CommandBase::AddRequirements( @@ -37,14 +31,20 @@ wpi::SmallSet CommandBase::GetRequirements() const { return m_requirements; } -void CommandBase::SetName(const wpi::Twine& name) { m_name = name.str(); } +void CommandBase::SetName(const wpi::Twine& name) { + frc::SendableRegistry::GetInstance().SetName(this, name); +} -std::string CommandBase::GetName() const { return m_name; } +std::string CommandBase::GetName() const { + return frc::SendableRegistry::GetInstance().GetName(this); +} -std::string CommandBase::GetSubsystem() const { return m_subsystem; } +std::string CommandBase::GetSubsystem() const { + return frc::SendableRegistry::GetInstance().GetSubsystem(this); +} void CommandBase::SetSubsystem(const wpi::Twine& subsystem) { - m_subsystem = subsystem.str(); + frc::SendableRegistry::GetInstance().SetSubsystem(this, subsystem); } void CommandBase::InitSendable(frc::SendableBuilder& builder) { diff --git a/wpilibc/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/wpilibc/src/main/native/cpp/frc2/command/CommandScheduler.cpp index f1423d18fa..bb0bf8ede1 100644 --- a/wpilibc/src/main/native/cpp/frc2/command/CommandScheduler.cpp +++ b/wpilibc/src/main/native/cpp/frc2/command/CommandScheduler.cpp @@ -11,6 +11,7 @@ #include #include #include +#include #include #include @@ -22,7 +23,9 @@ static bool ContainsKey(const TMap& map, TKey keyToCheck) { return map.find(keyToCheck) != map.end(); } -CommandScheduler::CommandScheduler() { SetName("Scheduler"); } +CommandScheduler::CommandScheduler() { + frc::SendableRegistry::GetInstance().AddLW(this, "Scheduler"); +} CommandScheduler& CommandScheduler::GetInstance() { static CommandScheduler scheduler; diff --git a/wpilibc/src/main/native/cpp/frc2/command/SubsystemBase.cpp b/wpilibc/src/main/native/cpp/frc2/command/SubsystemBase.cpp index 62080435dd..226f080655 100644 --- a/wpilibc/src/main/native/cpp/frc2/command/SubsystemBase.cpp +++ b/wpilibc/src/main/native/cpp/frc2/command/SubsystemBase.cpp @@ -7,15 +7,15 @@ #include "frc2/command/SubsystemBase.h" -#include #include +#include #include #include using namespace frc2; SubsystemBase::SubsystemBase() { - m_name = GetTypeName(*this); + frc::SendableRegistry::GetInstance().AddLW(this, GetTypeName(*this)); CommandScheduler::GetInstance().RegisterSubsystem({this}); } @@ -43,15 +43,24 @@ void SubsystemBase::InitSendable(frc::SendableBuilder& builder) { nullptr); } -std::string SubsystemBase::GetName() const { return m_name; } +std::string SubsystemBase::GetName() const { + return frc::SendableRegistry::GetInstance().GetName(this); +} -void SubsystemBase::SetName(const wpi::Twine& name) { m_name = name.str(); } +void SubsystemBase::SetName(const wpi::Twine& name) { + frc::SendableRegistry::GetInstance().SetName(this, name); +} -std::string SubsystemBase::GetSubsystem() const { return GetName(); } +std::string SubsystemBase::GetSubsystem() const { + return frc::SendableRegistry::GetInstance().GetSubsystem(this); +} -void SubsystemBase::SetSubsystem(const wpi::Twine& name) { SetName(name); } +void SubsystemBase::SetSubsystem(const wpi::Twine& name) { + frc::SendableRegistry::GetInstance().SetSubsystem(this, name); +} void SubsystemBase::AddChild(std::string name, frc::Sendable* child) { - child->SetName(name); - frc::LiveWindow::GetInstance()->Add(child); + auto& registry = frc::SendableRegistry::GetInstance(); + registry.AddLW(child, GetSubsystem(), name); + registry.AddChild(this, child); } diff --git a/wpilibc/src/main/native/cpp/frc2/command/WaitCommand.cpp b/wpilibc/src/main/native/cpp/frc2/command/WaitCommand.cpp index ef794cb548..1279d66986 100644 --- a/wpilibc/src/main/native/cpp/frc2/command/WaitCommand.cpp +++ b/wpilibc/src/main/native/cpp/frc2/command/WaitCommand.cpp @@ -11,7 +11,7 @@ using namespace frc2; WaitCommand::WaitCommand(units::second_t duration) : m_duration{duration} { auto durationStr = std::to_string(duration.to()); - SetName(wpi::Twine(m_name) + ": " + wpi::Twine(durationStr) + " seconds"); + SetName(wpi::Twine(GetName()) + ": " + wpi::Twine(durationStr) + " seconds"); } void WaitCommand::Initialize() { diff --git a/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp b/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp index 51688f3873..0c8801bbd2 100644 --- a/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp +++ b/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp @@ -7,18 +7,14 @@ #include "frc/livewindow/LiveWindow.h" -#include - #include #include #include -#include -#include #include -#include #include "frc/commands/Scheduler.h" #include "frc/smartdashboard/SendableBuilderImpl.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -28,8 +24,6 @@ struct LiveWindow::Impl { Impl(); struct Component { - std::shared_ptr sendable; - Sendable* parent = nullptr; SendableBuilderImpl builder; bool firstTime = true; bool telemetryEnabled = true; @@ -37,7 +31,8 @@ struct LiveWindow::Impl { wpi::mutex mutex; - wpi::DenseMap components; + SendableRegistry& registry; + int dataHandle; std::shared_ptr liveWindowTable; std::shared_ptr statusTable; @@ -46,64 +41,57 @@ struct LiveWindow::Impl { bool startLiveWindow = false; bool liveWindowEnabled = false; bool telemetryEnabled = true; + + std::shared_ptr GetOrAdd(Sendable* sendable); }; LiveWindow::Impl::Impl() - : liveWindowTable( + : registry(SendableRegistry::GetInstance()), + dataHandle(registry.GetDataHandle()), + liveWindowTable( nt::NetworkTableInstance::GetDefault().GetTable("LiveWindow")) { statusTable = liveWindowTable->GetSubTable(".status"); enabledEntry = statusTable->GetEntry("LW Enabled"); } +std::shared_ptr LiveWindow::Impl::GetOrAdd( + Sendable* sendable) { + auto data = std::static_pointer_cast( + registry.GetData(sendable, dataHandle)); + if (!data) { + data = std::make_shared(); + registry.SetData(sendable, dataHandle, data); + } + return data; +} + LiveWindow* LiveWindow::GetInstance() { static LiveWindow instance; return &instance; } -void LiveWindow::Add(std::shared_ptr sendable) { - std::scoped_lock lock(m_impl->mutex); - auto& comp = m_impl->components[sendable.get()]; - comp.sendable = sendable; -} - -void LiveWindow::Add(Sendable* sendable) { - Add(std::shared_ptr(sendable, NullDeleter())); -} - -void LiveWindow::AddChild(Sendable* parent, std::shared_ptr child) { - AddChild(parent, child.get()); -} - -void LiveWindow::AddChild(Sendable* parent, void* child) { - std::scoped_lock lock(m_impl->mutex); - auto& comp = m_impl->components[child]; - comp.parent = parent; - comp.telemetryEnabled = false; -} - -bool LiveWindow::Remove(Sendable* sendable) { - std::scoped_lock lock(m_impl->mutex); - return m_impl->components.erase(sendable); -} - void LiveWindow::EnableTelemetry(Sendable* sendable) { std::scoped_lock lock(m_impl->mutex); // Re-enable global setting in case DisableAllTelemetry() was called. m_impl->telemetryEnabled = true; - auto i = m_impl->components.find(sendable); - if (i != m_impl->components.end()) i->getSecond().telemetryEnabled = true; + m_impl->GetOrAdd(sendable)->telemetryEnabled = true; } void LiveWindow::DisableTelemetry(Sendable* sendable) { std::scoped_lock lock(m_impl->mutex); - auto i = m_impl->components.find(sendable); - if (i != m_impl->components.end()) i->getSecond().telemetryEnabled = false; + m_impl->GetOrAdd(sendable)->telemetryEnabled = false; } void LiveWindow::DisableAllTelemetry() { std::scoped_lock lock(m_impl->mutex); m_impl->telemetryEnabled = false; - for (auto& i : m_impl->components) i.getSecond().telemetryEnabled = false; + m_impl->registry.ForeachLiveWindow( + m_impl->dataHandle, [&](Sendable*, wpi::StringRef, wpi::StringRef, + Sendable*, std::shared_ptr& data) { + if (!data) data = std::make_shared(); + std::static_pointer_cast(data)->telemetryEnabled = + false; + }); } bool LiveWindow::IsEnabled() const { @@ -123,9 +111,13 @@ void LiveWindow::SetEnabled(bool enabled) { scheduler->SetEnabled(false); scheduler->RemoveAll(); } else { - for (auto& i : m_impl->components) { - i.getSecond().builder.StopLiveWindowMode(); - } + m_impl->registry.ForeachLiveWindow( + m_impl->dataHandle, [&](Sendable*, wpi::StringRef, wpi::StringRef, + Sendable*, std::shared_ptr& data) { + if (data) + std::static_pointer_cast(data) + ->builder.StopLiveWindowMode(); + }); scheduler->SetEnabled(true); } m_impl->enabledEntry.SetBoolean(enabled); @@ -140,37 +132,42 @@ void LiveWindow::UpdateValuesUnsafe() { // Only do this if either LiveWindow mode or telemetry is enabled. if (!m_impl->liveWindowEnabled && !m_impl->telemetryEnabled) return; - for (auto& i : m_impl->components) { - auto& comp = i.getSecond(); - if (comp.sendable && !comp.parent && - (m_impl->liveWindowEnabled || comp.telemetryEnabled)) { - 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. - auto name = comp.sendable->GetName(); - if (name.empty()) continue; - auto subsystem = comp.sendable->GetSubsystem(); - auto ssTable = m_impl->liveWindowTable->GetSubTable(subsystem); - std::shared_ptr table; - // Treat name==subsystem as top level of subsystem - if (name == subsystem) - table = ssTable; - else - table = ssTable->GetSubTable(name); - table->GetEntry(".name").SetString(name); - comp.builder.SetTable(table); - comp.sendable->InitSendable(comp.builder); - ssTable->GetEntry(".type").SetString("LW Subsystem"); + m_impl->registry.ForeachLiveWindow( + m_impl->dataHandle, + [&](Sendable* sendable, wpi::StringRef name, wpi::StringRef subsystem, + Sendable* parent, std::shared_ptr& data) { + if (!sendable || parent) return; - comp.firstTime = false; - } + if (!data) data = std::make_shared(); - if (m_impl->startLiveWindow) comp.builder.StartLiveWindowMode(); - comp.builder.UpdateTable(); - } - } + auto& comp = *std::static_pointer_cast(data); + + if (!m_impl->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 (name.empty()) return; + auto ssTable = m_impl->liveWindowTable->GetSubTable(subsystem); + std::shared_ptr table; + // Treat name==subsystem as top level of subsystem + if (name == subsystem) + table = ssTable; + else + table = ssTable->GetSubTable(name); + table->GetEntry(".name").SetString(name); + comp.builder.SetTable(table); + sendable->InitSendable(comp.builder); + ssTable->GetEntry(".type").SetString("LW Subsystem"); + + comp.firstTime = false; + } + + if (m_impl->startLiveWindow) comp.builder.StartLiveWindowMode(); + comp.builder.UpdateTable(); + }); m_impl->startLiveWindow = false; } diff --git a/wpilibc/src/main/native/cpp/shuffleboard/SendableCameraWrapper.cpp b/wpilibc/src/main/native/cpp/shuffleboard/SendableCameraWrapper.cpp index 87d7e9d882..97add4aabd 100644 --- a/wpilibc/src/main/native/cpp/shuffleboard/SendableCameraWrapper.cpp +++ b/wpilibc/src/main/native/cpp/shuffleboard/SendableCameraWrapper.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,6 +11,7 @@ #include #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -33,10 +34,10 @@ SendableCameraWrapper& SendableCameraWrapper::Wrap(CS_Source source) { SendableCameraWrapper::SendableCameraWrapper(CS_Source source, const private_init&) - : SendableBase(false), m_uri(kProtocol) { + : m_uri(kProtocol) { CS_Status status = 0; auto name = cs::GetSourceName(source, &status); - SetName(name); + SendableRegistry::GetInstance().Add(this, name); m_uri += name; } diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp index ffcc5217ce..c36e537020 100644 --- a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp +++ b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp @@ -15,6 +15,7 @@ #include "frc/shuffleboard/ShuffleboardComponent.h" #include "frc/shuffleboard/ShuffleboardLayout.h" #include "frc/shuffleboard/SimpleWidget.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -80,10 +81,11 @@ ComplexWidget& ShuffleboardContainer::Add(const wpi::Twine& title, } ComplexWidget& ShuffleboardContainer::Add(Sendable& sendable) { - if (sendable.GetName().empty()) { + auto name = SendableRegistry::GetInstance().GetName(&sendable); + if (name.empty()) { wpi::outs() << "Sendable must have a name\n"; } - return Add(sendable.GetName(), sendable); + return Add(name, sendable); } ComplexWidget& ShuffleboardContainer::Add(const cs::VideoSource& video) { diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableBase.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableBase.cpp index 96f054554c..7fc8635e5a 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SendableBase.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableBase.cpp @@ -7,62 +7,13 @@ #include "frc/smartdashboard/SendableBase.h" -#include - -#include "frc/livewindow/LiveWindow.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; SendableBase::SendableBase(bool addLiveWindow) { - if (addLiveWindow) LiveWindow::GetInstance()->Add(this); -} - -SendableBase::SendableBase(SendableBase&& other) - : m_name(std::move(other.m_name)), - m_subsystem(std::move(other.m_subsystem)) { - auto&& lw = LiveWindow::GetInstance(); - if (lw->Remove(&other)) { - lw->Add(this); - } -} - -SendableBase& SendableBase::operator=(SendableBase&& other) { - m_name = std::move(other.m_name); - m_subsystem = std::move(other.m_subsystem); - auto&& lw = LiveWindow::GetInstance(); - if (lw->Remove(&other)) { - lw->Add(this); - } - - return *this; -} - -SendableBase::~SendableBase() { LiveWindow::GetInstance()->Remove(this); } - -std::string SendableBase::GetName() const { return m_name; } - -void SendableBase::SetName(const wpi::Twine& name) { m_name = name.str(); } - -std::string SendableBase::GetSubsystem() const { return m_subsystem; } - -void SendableBase::SetSubsystem(const wpi::Twine& subsystem) { - m_subsystem = subsystem.str(); -} - -void SendableBase::AddChild(std::shared_ptr child) { - LiveWindow::GetInstance()->AddChild(this, child); -} - -void SendableBase::AddChild(void* child) { - LiveWindow::GetInstance()->AddChild(this, child); -} - -void SendableBase::SetName(const wpi::Twine& moduleType, int channel) { - SetName(moduleType + wpi::Twine('[') + wpi::Twine(channel) + wpi::Twine(']')); -} - -void SendableBase::SetName(const wpi::Twine& moduleType, int moduleNumber, - int channel) { - SetName(moduleType + wpi::Twine('[') + wpi::Twine(moduleNumber) + - wpi::Twine(',') + wpi::Twine(channel) + wpi::Twine(']')); + if (addLiveWindow) + SendableRegistry::GetInstance().AddLW(this, ""); + else + SendableRegistry::GetInstance().Add(this, ""); } diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp index 2cdf92cd4e..419b8d6acf 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -7,9 +7,12 @@ #include "frc/smartdashboard/SendableChooserBase.h" +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; std::atomic_int SendableChooserBase::s_instances{0}; -SendableChooserBase::SendableChooserBase() - : SendableBase(false), m_instance{s_instances++} {} +SendableChooserBase::SendableChooserBase() : m_instance{s_instances++} { + SendableRegistry::GetInstance().Add(this, "SendableChooser", m_instance); +} diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableRegistry.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableRegistry.cpp new file mode 100644 index 0000000000..d6ad48a34c --- /dev/null +++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableRegistry.cpp @@ -0,0 +1,263 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +#include "frc/smartdashboard/SendableRegistry.h" + +#include +#include +#include + +using namespace frc; + +struct SendableRegistry::Impl { + struct Component { + Sendable* sendable = nullptr; + std::string name; + std::string subsystem = "Ungrouped"; + Sendable* parent = nullptr; + bool liveWindow = false; + wpi::SmallVector, 2> data; + + void SetName(const wpi::Twine& moduleType, int channel) { + name = + (moduleType + wpi::Twine('[') + wpi::Twine(channel) + wpi::Twine(']')) + .str(); + } + + void SetName(const wpi::Twine& moduleType, int moduleNumber, int channel) { + name = (moduleType + wpi::Twine('[') + wpi::Twine(moduleNumber) + + wpi::Twine(',') + wpi::Twine(channel) + wpi::Twine(']')) + .str(); + } + }; + + wpi::mutex mutex; + + wpi::DenseMap components; + int nextDataHandle = 0; + + Component& GetOrAdd(Sendable* sendable); +}; + +SendableRegistry::Impl::Component& SendableRegistry::Impl::GetOrAdd( + Sendable* sendable) { + auto& comp = components[sendable]; + comp.sendable = sendable; + return comp; +} + +SendableRegistry& SendableRegistry::GetInstance() { + static SendableRegistry instance; + return instance; +} + +void SendableRegistry::Add(Sendable* sendable, const wpi::Twine& name) { + std::scoped_lock lock(m_impl->mutex); + auto& comp = m_impl->GetOrAdd(sendable); + comp.name = name.str(); +} + +void SendableRegistry::Add(Sendable* sendable, const wpi::Twine& moduleType, + int channel) { + std::scoped_lock lock(m_impl->mutex); + auto& comp = m_impl->GetOrAdd(sendable); + comp.SetName(moduleType, channel); +} + +void SendableRegistry::Add(Sendable* sendable, const wpi::Twine& moduleType, + int moduleNumber, int channel) { + std::scoped_lock lock(m_impl->mutex); + auto& comp = m_impl->GetOrAdd(sendable); + comp.SetName(moduleType, moduleNumber, channel); +} + +void SendableRegistry::Add(Sendable* sendable, const wpi::Twine& subsystem, + const wpi::Twine& name) { + std::scoped_lock lock(m_impl->mutex); + auto& comp = m_impl->GetOrAdd(sendable); + comp.name = name.str(); + comp.subsystem = subsystem.str(); +} + +void SendableRegistry::AddLW(Sendable* sendable, const wpi::Twine& name) { + std::scoped_lock lock(m_impl->mutex); + auto& comp = m_impl->GetOrAdd(sendable); + comp.liveWindow = true; + comp.name = name.str(); +} + +void SendableRegistry::AddLW(Sendable* sendable, const wpi::Twine& moduleType, + int channel) { + std::scoped_lock lock(m_impl->mutex); + auto& comp = m_impl->GetOrAdd(sendable); + comp.liveWindow = true; + comp.SetName(moduleType, channel); +} + +void SendableRegistry::AddLW(Sendable* sendable, const wpi::Twine& moduleType, + int moduleNumber, int channel) { + std::scoped_lock lock(m_impl->mutex); + auto& comp = m_impl->GetOrAdd(sendable); + comp.liveWindow = true; + comp.SetName(moduleType, moduleNumber, channel); +} + +void SendableRegistry::AddLW(Sendable* sendable, const wpi::Twine& subsystem, + const wpi::Twine& name) { + std::scoped_lock lock(m_impl->mutex); + auto& comp = m_impl->GetOrAdd(sendable); + comp.liveWindow = true; + comp.name = name.str(); + comp.subsystem = subsystem.str(); +} + +void SendableRegistry::AddChild(Sendable* parent, void* child) { + std::scoped_lock lock(m_impl->mutex); + auto& comp = m_impl->components[child]; + comp.parent = parent; +} + +bool SendableRegistry::Remove(Sendable* sendable) { + std::scoped_lock lock(m_impl->mutex); + return m_impl->components.erase(sendable); +} + +void SendableRegistry::Move(Sendable* to, Sendable* from) { + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(from); + if (it == m_impl->components.end()) return; + Impl::Component old = std::move(it->getSecond()); + m_impl->components.erase(it); + m_impl->components[to] = std::move(old); + m_impl->components[to].sendable = to; +} + +bool SendableRegistry::Contains(const Sendable* sendable) const { + std::scoped_lock lock(m_impl->mutex); + return m_impl->components.count(sendable) != 0; +} + +std::string SendableRegistry::GetName(const Sendable* sendable) const { + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return std::string{}; + return it->getSecond().name; +} + +void SendableRegistry::SetName(Sendable* sendable, const wpi::Twine& name) { + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return; + it->getSecond().name = name.str(); +} + +void SendableRegistry::SetName(Sendable* sendable, const wpi::Twine& moduleType, + int channel) { + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return; + it->getSecond().SetName(moduleType, channel); +} + +void SendableRegistry::SetName(Sendable* sendable, const wpi::Twine& moduleType, + int moduleNumber, int channel) { + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return; + it->getSecond().SetName(moduleType, moduleNumber, channel); +} + +void SendableRegistry::SetName(Sendable* sendable, const wpi::Twine& subsystem, + const wpi::Twine& name) { + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return; + it->getSecond().name = name.str(); + it->getSecond().subsystem = subsystem.str(); +} + +std::string SendableRegistry::GetSubsystem(const Sendable* sendable) const { + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return std::string{}; + return it->getSecond().subsystem; +} + +void SendableRegistry::SetSubsystem(Sendable* sendable, + const wpi::Twine& subsystem) { + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return; + it->getSecond().subsystem = subsystem.str(); +} + +int SendableRegistry::GetDataHandle() { + std::scoped_lock lock(m_impl->mutex); + return m_impl->nextDataHandle++; +} + +std::shared_ptr SendableRegistry::SetData(Sendable* sendable, int handle, + std::shared_ptr data) { + assert(handle >= 0); + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return nullptr; + auto& comp = it->getSecond(); + std::shared_ptr rv; + if (static_cast(handle) < comp.data.size()) + rv = std::move(comp.data[handle]); + else + comp.data.resize(handle + 1); + comp.data[handle] = std::move(data); + return rv; +} + +std::shared_ptr SendableRegistry::GetData(Sendable* sendable, + int handle) { + assert(handle >= 0); + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return nullptr; + auto& comp = it->getSecond(); + if (static_cast(handle) >= comp.data.size()) return nullptr; + return comp.data[handle]; +} + +void SendableRegistry::EnableLiveWindow(Sendable* sendable) { + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return; + it->getSecond().liveWindow = true; +} + +void SendableRegistry::DisableLiveWindow(Sendable* sendable) { + std::scoped_lock lock(m_impl->mutex); + auto it = m_impl->components.find(sendable); + if (it == m_impl->components.end()) return; + it->getSecond().liveWindow = false; +} + +void SendableRegistry::ForeachLiveWindow( + int dataHandle, + wpi::function_ref& data)> + callback) const { + assert(dataHandle >= 0); + std::scoped_lock lock(m_impl->mutex); + for (auto& i : m_impl->components) { + auto& comp = i.getSecond(); + if (comp.sendable && comp.liveWindow) { + if (static_cast(dataHandle) >= comp.data.size()) + comp.data.resize(dataHandle + 1); + callback(comp.sendable, comp.name, comp.subsystem, comp.parent, + comp.data[dataHandle]); + } + } +} + +SendableRegistry::SendableRegistry() : m_impl(new Impl) {} diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp index 9c89e49af3..9d0a366cff 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp @@ -14,8 +14,8 @@ #include #include "frc/WPIErrors.h" -#include "frc/smartdashboard/Sendable.h" #include "frc/smartdashboard/SendableBuilderImpl.h" +#include "frc/smartdashboard/SendableRegistry.h" using namespace frc; @@ -115,7 +115,8 @@ void SmartDashboard::PutData(Sendable* value) { wpi_setGlobalWPIErrorWithContext(NullParameter, "value"); return; } - PutData(value->GetName(), value); + auto name = SendableRegistry::GetInstance().GetName(value); + if (!name.empty()) PutData(name, value); } Sendable* SmartDashboard::GetData(wpi::StringRef key) { diff --git a/wpilibc/src/main/native/include/frc/ADXL345_I2C.h b/wpilibc/src/main/native/include/frc/ADXL345_I2C.h index 5d5fed41fd..eb40965669 100644 --- a/wpilibc/src/main/native/include/frc/ADXL345_I2C.h +++ b/wpilibc/src/main/native/include/frc/ADXL345_I2C.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,10 +10,13 @@ #include "frc/ErrorBase.h" #include "frc/I2C.h" #include "frc/interfaces/Accelerometer.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * ADXL345 Accelerometer on I2C. * @@ -22,8 +25,9 @@ namespace frc { * 0x1D (7-bit address). */ class ADXL345_I2C : public ErrorBase, - public SendableBase, - public Accelerometer { + public Accelerometer, + public Sendable, + public SendableHelper { public: enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 }; diff --git a/wpilibc/src/main/native/include/frc/ADXL345_SPI.h b/wpilibc/src/main/native/include/frc/ADXL345_SPI.h index ac5d6d9739..c242b368fe 100644 --- a/wpilibc/src/main/native/include/frc/ADXL345_SPI.h +++ b/wpilibc/src/main/native/include/frc/ADXL345_SPI.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,7 +10,8 @@ #include "frc/ErrorBase.h" #include "frc/SPI.h" #include "frc/interfaces/Accelerometer.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -21,8 +22,9 @@ namespace frc { * via SPI. This class assumes the sensor is wired in 4-wire SPI mode. */ class ADXL345_SPI : public ErrorBase, - public SendableBase, - public Accelerometer { + public Accelerometer, + public Sendable, + public SendableHelper { public: enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 }; diff --git a/wpilibc/src/main/native/include/frc/ADXL362.h b/wpilibc/src/main/native/include/frc/ADXL362.h index 896af15439..6de440fb4e 100644 --- a/wpilibc/src/main/native/include/frc/ADXL362.h +++ b/wpilibc/src/main/native/include/frc/ADXL362.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,16 +10,22 @@ #include "frc/ErrorBase.h" #include "frc/SPI.h" #include "frc/interfaces/Accelerometer.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * ADXL362 SPI Accelerometer. * * This class allows access to an Analog Devices ADXL362 3-axis accelerometer. */ -class ADXL362 : public ErrorBase, public SendableBase, public Accelerometer { +class ADXL362 : public ErrorBase, + public Accelerometer, + public Sendable, + public SendableHelper { public: enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 }; struct AllAxes { @@ -44,7 +50,7 @@ class ADXL362 : public ErrorBase, public SendableBase, public Accelerometer { */ explicit ADXL362(SPI::Port port, Range range = kRange_2G); - virtual ~ADXL362() = default; + ~ADXL362() override = default; ADXL362(ADXL362&&) = default; ADXL362& operator=(ADXL362&&) = default; diff --git a/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h b/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h index e1b70e25f8..598e54b739 100644 --- a/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h +++ b/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2015-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2015-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -40,7 +40,7 @@ class ADXRS450_Gyro : public GyroBase { */ explicit ADXRS450_Gyro(SPI::Port port); - virtual ~ADXRS450_Gyro() = default; + ~ADXRS450_Gyro() override = default; ADXRS450_Gyro(ADXRS450_Gyro&&) = default; ADXRS450_Gyro& operator=(ADXRS450_Gyro&&) = default; diff --git a/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h b/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h index 80dc98ec02..27015e46fe 100644 --- a/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h +++ b/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,10 +12,13 @@ #include "frc/AnalogInput.h" #include "frc/ErrorBase.h" #include "frc/PIDSource.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Handle operation of an analog accelerometer. * @@ -24,8 +27,9 @@ namespace frc { * calibrated by finding the center value over a period of time. */ class AnalogAccelerometer : public ErrorBase, - public SendableBase, - public PIDSource { + public PIDSource, + public Sendable, + public SendableHelper { public: /** * Create a new instance of an accelerometer. diff --git a/wpilibc/src/main/native/include/frc/AnalogGyro.h b/wpilibc/src/main/native/include/frc/AnalogGyro.h index 3e7ec7ddd3..bcc67c96e6 100644 --- a/wpilibc/src/main/native/include/frc/AnalogGyro.h +++ b/wpilibc/src/main/native/include/frc/AnalogGyro.h @@ -12,6 +12,8 @@ #include #include "frc/GyroBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -100,7 +102,7 @@ class AnalogGyro : public GyroBase { */ AnalogGyro(std::shared_ptr channel, int center, double offset); - virtual ~AnalogGyro(); + ~AnalogGyro() override; AnalogGyro(AnalogGyro&& rhs); AnalogGyro& operator=(AnalogGyro&& rhs); diff --git a/wpilibc/src/main/native/include/frc/AnalogInput.h b/wpilibc/src/main/native/include/frc/AnalogInput.h index fe74b04086..143721aa6d 100644 --- a/wpilibc/src/main/native/include/frc/AnalogInput.h +++ b/wpilibc/src/main/native/include/frc/AnalogInput.h @@ -13,10 +13,13 @@ #include "frc/ErrorBase.h" #include "frc/PIDSource.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Analog input class. * @@ -29,7 +32,10 @@ namespace frc { * are divided by the number of samples to retain the resolution, but get more * stable values. */ -class AnalogInput : public ErrorBase, public SendableBase, public PIDSource { +class AnalogInput : public ErrorBase, + public PIDSource, + public Sendable, + public SendableHelper { friend class AnalogTrigger; friend class AnalogGyro; diff --git a/wpilibc/src/main/native/include/frc/AnalogOutput.h b/wpilibc/src/main/native/include/frc/AnalogOutput.h index d42e9461da..1cecd707bb 100644 --- a/wpilibc/src/main/native/include/frc/AnalogOutput.h +++ b/wpilibc/src/main/native/include/frc/AnalogOutput.h @@ -10,14 +10,19 @@ #include #include "frc/ErrorBase.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * MXP analog output class. */ -class AnalogOutput : public ErrorBase, public SendableBase { +class AnalogOutput : public ErrorBase, + public Sendable, + public SendableHelper { public: /** * Construct an analog output on the given channel. diff --git a/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h b/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h index a937c698c5..446a9202d8 100644 --- a/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h +++ b/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,10 +12,13 @@ #include "frc/AnalogInput.h" #include "frc/ErrorBase.h" #include "frc/interfaces/Potentiometer.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Class for reading analog potentiometers. Analog potentiometers read in an * analog voltage that corresponds to a position. The position is in whichever @@ -23,8 +26,9 @@ namespace frc { * constructor. */ class AnalogPotentiometer : public ErrorBase, - public SendableBase, - public Potentiometer { + public Potentiometer, + public Sendable, + public SendableHelper { public: /** * Construct an Analog Potentiometer object from a channel number. diff --git a/wpilibc/src/main/native/include/frc/AnalogTrigger.h b/wpilibc/src/main/native/include/frc/AnalogTrigger.h index 618d3c2730..6a57f8a833 100644 --- a/wpilibc/src/main/native/include/frc/AnalogTrigger.h +++ b/wpilibc/src/main/native/include/frc/AnalogTrigger.h @@ -13,13 +13,17 @@ #include "frc/AnalogTriggerOutput.h" #include "frc/ErrorBase.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { class AnalogInput; +class SendableBuilder; -class AnalogTrigger : public ErrorBase, public SendableBase { +class AnalogTrigger : public ErrorBase, + public Sendable, + public SendableHelper { friend class AnalogTriggerOutput; public: diff --git a/wpilibc/src/main/native/include/frc/AnalogTriggerOutput.h b/wpilibc/src/main/native/include/frc/AnalogTriggerOutput.h index 931b3449fe..989a93f645 100644 --- a/wpilibc/src/main/native/include/frc/AnalogTriggerOutput.h +++ b/wpilibc/src/main/native/include/frc/AnalogTriggerOutput.h @@ -8,6 +8,8 @@ #pragma once #include "frc/DigitalSource.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -44,7 +46,9 @@ class AnalogTrigger; * rollover transition is not sharp / clean enough. Using the averaging engine * may help with this, but rotational speeds of the sensor will then be limited. */ -class AnalogTriggerOutput : public DigitalSource { +class AnalogTriggerOutput : public DigitalSource, + public Sendable, + public SendableHelper { friend class AnalogTrigger; public: diff --git a/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h b/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h index 3c9fc4a543..8148e72db5 100644 --- a/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h +++ b/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,18 +9,22 @@ #include "frc/ErrorBase.h" #include "frc/interfaces/Accelerometer.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Built-in accelerometer. * * This class allows access to the roboRIO's internal accelerometer. */ class BuiltInAccelerometer : public ErrorBase, - public SendableBase, - public Accelerometer { + public Accelerometer, + public Sendable, + public SendableHelper { public: /** * Constructor. diff --git a/wpilibc/src/main/native/include/frc/Compressor.h b/wpilibc/src/main/native/include/frc/Compressor.h index f16f698158..a5e512c929 100644 --- a/wpilibc/src/main/native/include/frc/Compressor.h +++ b/wpilibc/src/main/native/include/frc/Compressor.h @@ -11,10 +11,13 @@ #include "frc/ErrorBase.h" #include "frc/SensorUtil.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Class for operating a compressor connected to a %PCM (Pneumatic Control * Module). @@ -30,7 +33,9 @@ namespace frc { * loop control. You can only turn off closed loop control, thereby stopping * the compressor from operating. */ -class Compressor : public ErrorBase, public SendableBase { +class Compressor : public ErrorBase, + public Sendable, + public SendableHelper { public: /** * Constructor. The default PCM ID is 0. diff --git a/wpilibc/src/main/native/include/frc/Counter.h b/wpilibc/src/main/native/include/frc/Counter.h index fdfb8c5771..50e39486fb 100644 --- a/wpilibc/src/main/native/include/frc/Counter.h +++ b/wpilibc/src/main/native/include/frc/Counter.h @@ -14,11 +14,13 @@ #include "frc/AnalogTrigger.h" #include "frc/CounterBase.h" #include "frc/ErrorBase.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { class DigitalGlitchFilter; +class SendableBuilder; /** * Class for counting the number of ticks on a digital input channel. @@ -30,7 +32,10 @@ class DigitalGlitchFilter; * All counters will immediately start counting - Reset() them if you need them * to be zeroed before use. */ -class Counter : public ErrorBase, public SendableBase, public CounterBase { +class Counter : public ErrorBase, + public CounterBase, + public Sendable, + public SendableHelper { public: enum Mode { kTwoPulse = 0, diff --git a/wpilibc/src/main/native/include/frc/DigitalGlitchFilter.h b/wpilibc/src/main/native/include/frc/DigitalGlitchFilter.h index f33955e61b..0690e53b96 100644 --- a/wpilibc/src/main/native/include/frc/DigitalGlitchFilter.h +++ b/wpilibc/src/main/native/include/frc/DigitalGlitchFilter.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2015-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2015-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -15,7 +15,8 @@ #include "frc/DigitalSource.h" #include "frc/ErrorBase.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -29,7 +30,9 @@ class Counter; * filter. The filter lets the user configure the time that an input must remain * high or low before it is classified as high or low. */ -class DigitalGlitchFilter : public ErrorBase, public SendableBase { +class DigitalGlitchFilter : public ErrorBase, + public Sendable, + public SendableHelper { public: DigitalGlitchFilter(); ~DigitalGlitchFilter() override; diff --git a/wpilibc/src/main/native/include/frc/DigitalInput.h b/wpilibc/src/main/native/include/frc/DigitalInput.h index 790e1ab8d7..c74f338e09 100644 --- a/wpilibc/src/main/native/include/frc/DigitalInput.h +++ b/wpilibc/src/main/native/include/frc/DigitalInput.h @@ -8,10 +8,13 @@ #pragma once #include "frc/DigitalSource.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { class DigitalGlitchFilter; +class SendableBuilder; /** * Class to read a digital input. @@ -22,7 +25,9 @@ class DigitalGlitchFilter; * as required. This class is only for devices like switches etc. that aren't * implemented anywhere else. */ -class DigitalInput : public DigitalSource { +class DigitalInput : public DigitalSource, + public Sendable, + public SendableHelper { public: /** * Create an instance of a Digital Input class. diff --git a/wpilibc/src/main/native/include/frc/DigitalOutput.h b/wpilibc/src/main/native/include/frc/DigitalOutput.h index 76c2a04a1f..69e4e1d60d 100644 --- a/wpilibc/src/main/native/include/frc/DigitalOutput.h +++ b/wpilibc/src/main/native/include/frc/DigitalOutput.h @@ -10,10 +10,13 @@ #include #include "frc/ErrorBase.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Class to write to digital outputs. * @@ -21,7 +24,9 @@ namespace frc { * elsewhere will allocate channels automatically so for those devices it * shouldn't be done here. */ -class DigitalOutput : public ErrorBase, public SendableBase { +class DigitalOutput : public ErrorBase, + public Sendable, + public SendableHelper { public: /** * Create an instance of a digital output. diff --git a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h index 4edf9276de..67229765c1 100644 --- a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h +++ b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h @@ -10,9 +10,13 @@ #include #include "frc/SolenoidBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * DoubleSolenoid class for running 2 channels of high voltage Digital Output * (PCM). @@ -20,7 +24,9 @@ namespace frc { * The DoubleSolenoid class is typically used for pneumatics solenoids that * have two positions controlled by two separate channels. */ -class DoubleSolenoid : public SolenoidBase { +class DoubleSolenoid : public SolenoidBase, + public Sendable, + public SendableHelper { public: enum Value { kOff, kForward, kReverse }; diff --git a/wpilibc/src/main/native/include/frc/Encoder.h b/wpilibc/src/main/native/include/frc/Encoder.h index 03efbdb187..5350625f91 100644 --- a/wpilibc/src/main/native/include/frc/Encoder.h +++ b/wpilibc/src/main/native/include/frc/Encoder.h @@ -15,12 +15,14 @@ #include "frc/CounterBase.h" #include "frc/ErrorBase.h" #include "frc/PIDSource.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { class DigitalSource; class DigitalGlitchFilter; +class SendableBuilder; /** * Class to read quad encoders. @@ -38,9 +40,10 @@ class DigitalGlitchFilter; * to be zeroed before use. */ class Encoder : public ErrorBase, - public SendableBase, public CounterBase, - public PIDSource { + public PIDSource, + public Sendable, + public SendableHelper { public: enum IndexingType { kResetWhileHigh, diff --git a/wpilibc/src/main/native/include/frc/ErrorBase.h b/wpilibc/src/main/native/include/frc/ErrorBase.h index 095578a887..7235352bcd 100644 --- a/wpilibc/src/main/native/include/frc/ErrorBase.h +++ b/wpilibc/src/main/native/include/frc/ErrorBase.h @@ -79,6 +79,8 @@ class ErrorBase { ErrorBase(); virtual ~ErrorBase() = default; + ErrorBase(const ErrorBase&) = default; + ErrorBase& operator=(const ErrorBase&) = default; ErrorBase(ErrorBase&&) = default; ErrorBase& operator=(ErrorBase&&) = default; diff --git a/wpilibc/src/main/native/include/frc/GyroBase.h b/wpilibc/src/main/native/include/frc/GyroBase.h index d27c7d9262..037686f644 100644 --- a/wpilibc/src/main/native/include/frc/GyroBase.h +++ b/wpilibc/src/main/native/include/frc/GyroBase.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,7 +10,8 @@ #include "frc/ErrorBase.h" #include "frc/PIDSource.h" #include "frc/interfaces/Gyro.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -20,8 +21,9 @@ namespace frc { */ class GyroBase : public Gyro, public ErrorBase, - public SendableBase, - public PIDSource { + public PIDSource, + public Sendable, + public SendableHelper { public: GyroBase() = default; GyroBase(GyroBase&&) = default; diff --git a/wpilibc/src/main/native/include/frc/InterruptableSensorBase.h b/wpilibc/src/main/native/include/frc/InterruptableSensorBase.h index 527702f7e6..8c2a564d5a 100644 --- a/wpilibc/src/main/native/include/frc/InterruptableSensorBase.h +++ b/wpilibc/src/main/native/include/frc/InterruptableSensorBase.h @@ -14,11 +14,10 @@ #include "frc/AnalogTriggerType.h" #include "frc/ErrorBase.h" -#include "frc/smartdashboard/SendableBase.h" namespace frc { -class InterruptableSensorBase : public ErrorBase, public SendableBase { +class InterruptableSensorBase : public ErrorBase { public: enum WaitResult { kTimeout = 0x0, diff --git a/wpilibc/src/main/native/include/frc/NidecBrushless.h b/wpilibc/src/main/native/include/frc/NidecBrushless.h index 1d63c31373..ec0032b0ca 100644 --- a/wpilibc/src/main/native/include/frc/NidecBrushless.h +++ b/wpilibc/src/main/native/include/frc/NidecBrushless.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -14,16 +14,20 @@ #include "frc/MotorSafety.h" #include "frc/PWM.h" #include "frc/SpeedController.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Nidec Brushless Motor. */ -class NidecBrushless : public SendableBase, - public SpeedController, - public MotorSafety { +class NidecBrushless : public SpeedController, + public MotorSafety, + public Sendable, + public SendableHelper { public: /** * Constructor. diff --git a/wpilibc/src/main/native/include/frc/PIDBase.h b/wpilibc/src/main/native/include/frc/PIDBase.h index 63e7b02087..9181ba8bda 100644 --- a/wpilibc/src/main/native/include/frc/PIDBase.h +++ b/wpilibc/src/main/native/include/frc/PIDBase.h @@ -19,10 +19,13 @@ #include "frc/PIDOutput.h" #include "frc/PIDSource.h" #include "frc/Timer.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Class implements a PID Control Loop. * @@ -33,7 +36,10 @@ namespace frc { * in the integral and derivative calculations. Therefore, the sample rate * affects the controller's behavior for a given set of PID constants. */ -class PIDBase : public SendableBase, public PIDInterface, public PIDOutput { +class PIDBase : public PIDInterface, + public PIDOutput, + public Sendable, + public SendableHelper { public: /** * Allocate a PID object with the given constants for P, I, D. @@ -58,7 +64,7 @@ class PIDBase : public SendableBase, public PIDInterface, public PIDOutput { PIDBase(double p, double i, double d, double f, PIDSource& source, PIDOutput& output); - ~PIDBase() override = default; + virtual ~PIDBase() = default; PIDBase(PIDBase&&) = default; PIDBase& operator=(PIDBase&&) = default; diff --git a/wpilibc/src/main/native/include/frc/PWM.h b/wpilibc/src/main/native/include/frc/PWM.h index 08cbd4f175..58e18d2c1f 100644 --- a/wpilibc/src/main/native/include/frc/PWM.h +++ b/wpilibc/src/main/native/include/frc/PWM.h @@ -13,10 +13,13 @@ #include #include "frc/MotorSafety.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Class implements the PWM generation in the FPGA. * @@ -34,7 +37,7 @@ namespace frc { * - 1 = minimum pulse width (currently .5ms) * - 0 = disabled (i.e. PWM output is held low) */ -class PWM : public MotorSafety, public SendableBase { +class PWM : public MotorSafety, public Sendable, public SendableHelper { public: /** * Represents the amount to multiply the minimum servo-pulse pwm period by. diff --git a/wpilibc/src/main/native/include/frc/PWMSpeedController.h b/wpilibc/src/main/native/include/frc/PWMSpeedController.h index 522255997a..b827d30edf 100644 --- a/wpilibc/src/main/native/include/frc/PWMSpeedController.h +++ b/wpilibc/src/main/native/include/frc/PWMSpeedController.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ diff --git a/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h b/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h index d0ddf33ef3..433874b6f9 100644 --- a/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h +++ b/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h @@ -10,15 +10,20 @@ #include #include "frc/ErrorBase.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Class for getting voltage, current, temperature, power and energy from the * CAN PDP. */ -class PowerDistributionPanel : public ErrorBase, public SendableBase { +class PowerDistributionPanel : public ErrorBase, + public Sendable, + public SendableHelper { public: PowerDistributionPanel(); explicit PowerDistributionPanel(int module); diff --git a/wpilibc/src/main/native/include/frc/Relay.h b/wpilibc/src/main/native/include/frc/Relay.h index 3de58d29f9..c903fc04d4 100644 --- a/wpilibc/src/main/native/include/frc/Relay.h +++ b/wpilibc/src/main/native/include/frc/Relay.h @@ -14,10 +14,13 @@ #include "frc/ErrorBase.h" #include "frc/MotorSafety.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Class for Spike style relay outputs. * @@ -30,7 +33,9 @@ namespace frc { * independently for something that does not care about voltage polarity (like * a solenoid). */ -class Relay : public MotorSafety, public SendableBase { +class Relay : public MotorSafety, + public Sendable, + public SendableHelper { public: enum Value { kOff, kOn, kForward, kReverse }; enum Direction { kBothDirections, kForwardOnly, kReverseOnly }; diff --git a/wpilibc/src/main/native/include/frc/Solenoid.h b/wpilibc/src/main/native/include/frc/Solenoid.h index e6f012d59f..86a2839f54 100644 --- a/wpilibc/src/main/native/include/frc/Solenoid.h +++ b/wpilibc/src/main/native/include/frc/Solenoid.h @@ -10,16 +10,22 @@ #include #include "frc/SolenoidBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { +class SendableBuilder; + /** * Solenoid class for running high voltage Digital Output (PCM). * * The Solenoid class is typically used for pneumatics solenoids, but could be * used for any device within the current spec of the PCM. */ -class Solenoid : public SolenoidBase { +class Solenoid : public SolenoidBase, + public Sendable, + public SendableHelper { public: /** * Constructor using the default PCM ID (0). diff --git a/wpilibc/src/main/native/include/frc/SolenoidBase.h b/wpilibc/src/main/native/include/frc/SolenoidBase.h index fe9f32e0ed..314df5c9e8 100644 --- a/wpilibc/src/main/native/include/frc/SolenoidBase.h +++ b/wpilibc/src/main/native/include/frc/SolenoidBase.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -8,7 +8,6 @@ #pragma once #include "frc/ErrorBase.h" -#include "frc/smartdashboard/SendableBase.h" namespace frc { @@ -16,7 +15,7 @@ namespace frc { * SolenoidBase class is the common base class for the Solenoid and * DoubleSolenoid classes. */ -class SolenoidBase : public ErrorBase, public SendableBase { +class SolenoidBase : public ErrorBase { public: /** * Read all 8 solenoids as a single byte diff --git a/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h b/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h index 3f0c699ac4..80adf1cc07 100644 --- a/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h +++ b/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,11 +11,14 @@ #include #include "frc/SpeedController.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { -class SpeedControllerGroup : public SendableBase, public SpeedController { +class SpeedControllerGroup : public Sendable, + public SpeedController, + public SendableHelper { public: template explicit SpeedControllerGroup(SpeedController& speedController, diff --git a/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc b/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc index ba4b766982..5848746f4f 100644 --- a/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc +++ b/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -7,6 +7,8 @@ #pragma once +#include "frc/smartdashboard/SendableRegistry.h" + namespace frc { template @@ -14,10 +16,10 @@ SpeedControllerGroup::SpeedControllerGroup( SpeedController& speedController, SpeedControllers&... speedControllers) : m_speedControllers{speedController, speedControllers...} { for (auto& speedController : m_speedControllers) - AddChild(&speedController.get()); + SendableRegistry::GetInstance().AddChild(this, &speedController.get()); static int instances = 0; ++instances; - SetName("SpeedControllerGroup", instances); + SendableRegistry::GetInstance().Add(this, "SpeedControllerGroup", instances); } } // namespace frc diff --git a/wpilibc/src/main/native/include/frc/Ultrasonic.h b/wpilibc/src/main/native/include/frc/Ultrasonic.h index 82ae6ca0ed..0a0e5d2fdf 100644 --- a/wpilibc/src/main/native/include/frc/Ultrasonic.h +++ b/wpilibc/src/main/native/include/frc/Ultrasonic.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -15,7 +15,8 @@ #include "frc/Counter.h" #include "frc/ErrorBase.h" #include "frc/PIDSource.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -34,7 +35,10 @@ class DigitalOutput; * received. The time that the line is high determines the round trip distance * (time of flight). */ -class Ultrasonic : public ErrorBase, public SendableBase, public PIDSource { +class Ultrasonic : public ErrorBase, + public Sendable, + public PIDSource, + public SendableHelper { public: enum DistanceUnit { kInches = 0, kMilliMeters = 1 }; diff --git a/wpilibc/src/main/native/include/frc/buttons/Trigger.h b/wpilibc/src/main/native/include/frc/buttons/Trigger.h index 8f8c4779b3..4c7b01c61b 100644 --- a/wpilibc/src/main/native/include/frc/buttons/Trigger.h +++ b/wpilibc/src/main/native/include/frc/buttons/Trigger.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2011-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2011-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,7 +9,8 @@ #include -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -28,7 +29,7 @@ class Command; * only have to write the {@link Trigger#Get()} method to get the full * functionality of the Trigger class. */ -class Trigger : public SendableBase { +class Trigger : public Sendable, public SendableHelper { public: Trigger() = default; ~Trigger() override = default; diff --git a/wpilibc/src/main/native/include/frc/commands/Command.h b/wpilibc/src/main/native/include/frc/commands/Command.h index f1990c7101..d40bb0058c 100644 --- a/wpilibc/src/main/native/include/frc/commands/Command.h +++ b/wpilibc/src/main/native/include/frc/commands/Command.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2011-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2011-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -15,7 +15,8 @@ #include "frc/ErrorBase.h" #include "frc/commands/Subsystem.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -45,7 +46,9 @@ class CommandGroup; * @see CommandGroup * @see Subsystem */ -class Command : public ErrorBase, public SendableBase { +class Command : public ErrorBase, + public Sendable, + public SendableHelper { friend class CommandGroup; friend class Scheduler; @@ -385,6 +388,34 @@ class Command : public ErrorBase, public SendableBase { friend class ConditionalCommand; + /** + * Gets the name of this Command. + * + * @return Name + */ + std::string GetName() const; + + /** + * Sets the name of this Command. + * + * @param name name + */ + void SetName(const wpi::Twine& name); + + /** + * Gets the subsystem name of this Command. + * + * @return Subsystem name + */ + std::string GetSubsystem() const; + + /** + * Sets the subsystem name of this Command. + * + * @param subsystem subsystem name + */ + void SetSubsystem(const wpi::Twine& subsystem); + private: /** * Prevents further changes from being made. diff --git a/wpilibc/src/main/native/include/frc/commands/Scheduler.h b/wpilibc/src/main/native/include/frc/commands/Scheduler.h index c5c97baf51..d15ea393d5 100644 --- a/wpilibc/src/main/native/include/frc/commands/Scheduler.h +++ b/wpilibc/src/main/native/include/frc/commands/Scheduler.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2011-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2011-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,7 +10,8 @@ #include #include "frc/ErrorBase.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -18,7 +19,9 @@ class ButtonScheduler; class Command; class Subsystem; -class Scheduler : public ErrorBase, public SendableBase { +class Scheduler : public ErrorBase, + public Sendable, + public SendableHelper { public: /** * Returns the Scheduler, creating it if one does not exist. diff --git a/wpilibc/src/main/native/include/frc/commands/Subsystem.h b/wpilibc/src/main/native/include/frc/commands/Subsystem.h index bb6d166a0b..2637dd046c 100644 --- a/wpilibc/src/main/native/include/frc/commands/Subsystem.h +++ b/wpilibc/src/main/native/include/frc/commands/Subsystem.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2011-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2011-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -8,19 +8,22 @@ #pragma once #include +#include #include #include #include "frc/ErrorBase.h" #include "frc/smartdashboard/Sendable.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { class Command; -class Subsystem : public ErrorBase, public SendableBase { +class Subsystem : public ErrorBase, + public Sendable, + public SendableHelper { friend class Scheduler; public: @@ -97,6 +100,34 @@ class Subsystem : public ErrorBase, public SendableBase { */ virtual void InitDefaultCommand(); + /** + * Gets the name of this Subsystem. + * + * @return Name + */ + std::string GetName() const; + + /** + * Sets the name of this Subsystem. + * + * @param name name + */ + void SetName(const wpi::Twine& name); + + /** + * Gets the subsystem name of this Subsystem. + * + * @return Subsystem name + */ + std::string GetSubsystem() const; + + /** + * Sets the subsystem name of this Subsystem. + * + * @param subsystem subsystem name + */ + void SetSubsystem(const wpi::Twine& subsystem); + /** * Associate a Sendable with this Subsystem. * Also update the child's name. diff --git a/wpilibc/src/main/native/include/frc/controller/PIDController.h b/wpilibc/src/main/native/include/frc/controller/PIDController.h index c1000d7f94..66a36fb3fc 100644 --- a/wpilibc/src/main/native/include/frc/controller/PIDController.h +++ b/wpilibc/src/main/native/include/frc/controller/PIDController.h @@ -12,14 +12,16 @@ #include -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc2 { /** * Implements a PID control loop. */ -class PIDController : public frc::SendableBase { +class PIDController : public frc::Sendable, + public frc::SendableHelper { public: /** * Allocates a PIDController with the given constants for Kp, Ki, and Kd. diff --git a/wpilibc/src/main/native/include/frc/controller/ProfiledPIDController.h b/wpilibc/src/main/native/include/frc/controller/ProfiledPIDController.h index a39f76b0a6..a9837df8f7 100644 --- a/wpilibc/src/main/native/include/frc/controller/ProfiledPIDController.h +++ b/wpilibc/src/main/native/include/frc/controller/ProfiledPIDController.h @@ -13,7 +13,8 @@ #include #include "frc/controller/PIDController.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" #include "frc/trajectory/TrapezoidProfile.h" namespace frc { @@ -22,7 +23,8 @@ namespace frc { * Implements a PID control loop whose setpoint is constrained by a trapezoid * profile. */ -class ProfiledPIDController : public SendableBase { +class ProfiledPIDController : public Sendable, + public SendableHelper { public: /** * Allocates a ProfiledPIDController with the given constants for Kp, Ki, and diff --git a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h index cb12af5b97..6138f2c833 100644 --- a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h @@ -10,6 +10,8 @@ #include #include "frc/drive/RobotDriveBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -96,7 +98,9 @@ class SpeedController; * RobotDrive#Drive(double, double) with the addition of a quick turn * mode. However, it is not designed to give exactly the same response. */ -class DifferentialDrive : public RobotDriveBase { +class DifferentialDrive : public RobotDriveBase, + public Sendable, + public SendableHelper { public: static constexpr double kDefaultQuickStopThreshold = 0.2; static constexpr double kDefaultQuickStopAlpha = 0.1; diff --git a/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h b/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h index 2fa356dfe7..a35b59d667 100644 --- a/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -13,6 +13,8 @@ #include "frc/drive/RobotDriveBase.h" #include "frc/drive/Vector2d.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -44,7 +46,9 @@ class SpeedController; * and the positive Z axis points down. Rotations follow the right-hand rule, so * clockwise rotation around the Z axis is positive. */ -class KilloughDrive : public RobotDriveBase { +class KilloughDrive : public RobotDriveBase, + public Sendable, + public SendableHelper { public: static constexpr double kDefaultLeftMotorAngle = 60.0; static constexpr double kDefaultRightMotorAngle = 120.0; diff --git a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h index e0acaca6ab..7c3489e19b 100644 --- a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,6 +12,8 @@ #include #include "frc/drive/RobotDriveBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -62,7 +64,9 @@ class SpeedController; * RobotDrive#MecanumDrive_Polar(double, double, double) if a * deadband of 0 is used. */ -class MecanumDrive : public RobotDriveBase { +class MecanumDrive : public RobotDriveBase, + public Sendable, + public SendableHelper { public: /** * Construct a MecanumDrive. diff --git a/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h b/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h index 348a62e47d..ce9cbc5eb3 100644 --- a/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h +++ b/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h @@ -13,7 +13,6 @@ #include #include "frc/MotorSafety.h" -#include "frc/smartdashboard/SendableBase.h" namespace frc { @@ -22,7 +21,7 @@ class SpeedController; /** * Common base class for drive platforms. */ -class RobotDriveBase : public MotorSafety, public SendableBase { +class RobotDriveBase : public MotorSafety { public: /** * The location of a motor on the robot for the purpose of driving. diff --git a/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h b/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h index 575cb0c22d..c7e0ec2a83 100644 --- a/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h +++ b/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h @@ -9,13 +9,10 @@ #include -#include -#include - -#include "frc/smartdashboard/Sendable.h" - namespace frc { +class Sendable; + /** * The LiveWindow class is the public interface for putting sensors and * actuators on the LiveWindow. @@ -33,44 +30,6 @@ class LiveWindow { */ static LiveWindow* GetInstance(); - /** - * Add a component to the LiveWindow. - * - * @param sendable component to add - */ - void Add(std::shared_ptr component); - - /** - * Add a component to the LiveWindow. - * - * @param sendable component to add - */ - void Add(Sendable* component); - - /** - * Add a child component to a component. - * - * @param parent parent component - * @param child child component - */ - void AddChild(Sendable* parent, std::shared_ptr component); - - /** - * Add a child component to a component. - * - * @param parent parent component - * @param child child component - */ - void AddChild(Sendable* parent, void* component); - - /** - * Remove the component from the LiveWindow. - * - * @param sendable component to remove - * @return true if the component was removed; false if it was not present - */ - bool Remove(Sendable* component); - /** * Enable telemetry for a single component. * diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h b/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h index 291e64d459..b1a46d304e 100644 --- a/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h +++ b/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,7 +11,8 @@ #include -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace cs { class VideoSource; @@ -22,7 +23,8 @@ namespace frc { /** * A wrapper to make video sources sendable and usable from Shuffleboard. */ -class SendableCameraWrapper : public SendableBase { +class SendableCameraWrapper : public Sendable, + public SendableHelper { private: struct private_init {}; diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardLayout.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardLayout.h index e7baec993b..effa3da1f3 100644 --- a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardLayout.h +++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardLayout.h @@ -14,7 +14,6 @@ #include "frc/shuffleboard/ShuffleboardComponent.h" #include "frc/shuffleboard/ShuffleboardContainer.h" -#include "frc/smartdashboard/Sendable.h" #ifdef _WIN32 #pragma warning(push) diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardTab.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardTab.h index 16e6f92288..75896ae31b 100644 --- a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardTab.h +++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardTab.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -13,7 +13,6 @@ #include #include "frc/shuffleboard/ShuffleboardContainer.h" -#include "frc/smartdashboard/Sendable.h" namespace frc { diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/Sendable.h b/wpilibc/src/main/native/include/frc/smartdashboard/Sendable.h index 761b0bbcfe..500085526d 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/Sendable.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/Sendable.h @@ -7,63 +7,17 @@ #pragma once -#include - -#include - namespace frc { class SendableBuilder; +/** + * Interface for Sendable objects. + */ class Sendable { public: - Sendable() = default; virtual ~Sendable() = default; - Sendable(const Sendable&) = default; - Sendable& operator=(const Sendable&) = default; - Sendable(Sendable&&) = default; - Sendable& operator=(Sendable&&) = default; - - /** - * Gets the name of this Sendable object. - * - * @return Name - */ - virtual std::string GetName() const = 0; - - /** - * Sets the name of this Sendable object. - * - * @param name name - */ - virtual void SetName(const wpi::Twine& name) = 0; - - /** - * Sets both the subsystem name and device name of this Sendable object. - * - * @param subsystem subsystem name - * @param name device name - */ - void SetName(const wpi::Twine& subsystem, const wpi::Twine& name) { - SetSubsystem(subsystem); - SetName(name); - } - - /** - * Gets the subsystem name of this Sendable object. - * - * @return Subsystem name - */ - virtual std::string GetSubsystem() const = 0; - - /** - * Sets the subsystem name of this Sendable object. - * - * @param subsystem subsystem name - */ - virtual void SetSubsystem(const wpi::Twine& subsystem) = 0; - /** * Initializes this Sendable object. * diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBase.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBase.h index d2f0091eb6..a0ea0f93e2 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBase.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBase.h @@ -7,74 +7,22 @@ #pragma once -#include -#include +#include #include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { -class SendableBase : public Sendable { +class SendableBase : public Sendable, public SendableHelper { public: /** * Creates an instance of the sensor base. * * @param addLiveWindow if true, add this Sendable to LiveWindow */ + WPI_DEPRECATED("use Sendable and SendableHelper") explicit SendableBase(bool addLiveWindow = true); - - ~SendableBase() override; - - SendableBase(const SendableBase&) = default; - SendableBase& operator=(const SendableBase&) = default; - SendableBase(SendableBase&&); - SendableBase& operator=(SendableBase&&); - - using Sendable::SetName; - - std::string GetName() const final; - void SetName(const wpi::Twine& name) final; - std::string GetSubsystem() const final; - void SetSubsystem(const wpi::Twine& subsystem) final; - - protected: - /** - * Add a child component. - * - * @param child child component - */ - void AddChild(std::shared_ptr child); - - /** - * Add a child component. - * - * @param child child component - */ - void AddChild(void* child); - - /** - * Sets the name of the sensor with a channel number. - * - * @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 - */ - void SetName(const wpi::Twine& moduleType, int channel); - - /** - * Sets the name of the sensor with a module and channel number. - * - * @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 (usually - * PWM) - */ - void SetName(const wpi::Twine& moduleType, int moduleNumber, int channel); - - private: - std::string m_name; - std::string m_subsystem = "Ungrouped"; }; } // namespace frc diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h index ae7908ec43..b3447e3143 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -14,7 +14,8 @@ #include #include -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { @@ -24,7 +25,8 @@ namespace frc { * It contains static, non-templated variables to avoid their duplication in the * template class. */ -class SendableChooserBase : public SendableBase { +class SendableChooserBase : public Sendable, + public SendableHelper { public: SendableChooserBase(); ~SendableChooserBase() override = default; diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableHelper.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableHelper.h new file mode 100644 index 0000000000..6b0b28b624 --- /dev/null +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableHelper.h @@ -0,0 +1,161 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +#pragma once + +#include +#include + +#include +#include + +#include "frc/smartdashboard/SendableRegistry.h" + +namespace frc { + +/** + * A helper class for use with objects that add themselves to SendableRegistry. + * It takes care of properly calling Move() and Remove() on move and + * destruction. No action is taken if the object is copied. + * Use public inheritance with CRTP when using this class. + * @tparam CRTP derived class + */ +template +class SendableHelper { + public: + SendableHelper(const SendableHelper& rhs) = default; + SendableHelper& operator=(const SendableHelper& rhs) = default; + + SendableHelper(SendableHelper&& rhs) { + // it is safe to call Move() multiple times with the same rhs + SendableRegistry::GetInstance().Move(static_cast(this), + static_cast(&rhs)); + } + + SendableHelper& operator=(SendableHelper&& rhs) { + // it is safe to call Move() multiple times with the same rhs + SendableRegistry::GetInstance().Move(static_cast(this), + static_cast(&rhs)); + return *this; + } + + /** + * Gets the name of this Sendable object. + * + * @return Name + */ + WPI_DEPRECATED("use SendableRegistry::GetName()") + std::string GetName() const { + return SendableRegistry::GetInstance().GetName( + static_cast(this)); + } + + /** + * Sets the name of this Sendable object. + * + * @param name name + */ + WPI_DEPRECATED("use SendableRegistry::SetName()") + void SetName(const wpi::Twine& name) { + SendableRegistry::GetInstance().SetName(static_cast(this), name); + } + + /** + * Sets both the subsystem name and device name of this Sendable object. + * + * @param subsystem subsystem name + * @param name device name + */ + WPI_DEPRECATED("use SendableRegistry::SetName()") + void SetName(const wpi::Twine& subsystem, const wpi::Twine& name) { + SendableRegistry::GetInstance().SetName(static_cast(this), + subsystem, name); + } + + /** + * Gets the subsystem name of this Sendable object. + * + * @return Subsystem name + */ + WPI_DEPRECATED("use SendableRegistry::GetSubsystem()") + std::string GetSubsystem() const { + return SendableRegistry::GetInstance().GetSubsystem( + static_cast(this)); + } + + /** + * Sets the subsystem name of this Sendable object. + * + * @param subsystem subsystem name + */ + WPI_DEPRECATED("use SendableRegistry::SetSubsystem()") + void SetSubsystem(const wpi::Twine& subsystem) { + SendableRegistry::GetInstance().SetSubsystem(static_cast(this), + subsystem); + } + + protected: + /** + * Add a child component. + * + * @param child child component + */ + WPI_DEPRECATED("use SendableRegistry::AddChild()") + void AddChild(std::shared_ptr child) { + SendableRegistry::GetInstance().AddChild(static_cast(this), + child.get()); + } + + /** + * Add a child component. + * + * @param child child component + */ + WPI_DEPRECATED("use SendableRegistry::AddChild()") + void AddChild(void* child) { + SendableRegistry::GetInstance().AddChild(static_cast(this), + child); + } + + /** + * Sets the name of the sensor with a channel number. + * + * @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 + */ + WPI_DEPRECATED("use SendableRegistry::SetName()") + void SetName(const wpi::Twine& moduleType, int channel) { + SendableRegistry::GetInstance().SetName(static_cast(this), + moduleType, channel); + } + + /** + * Sets the name of the sensor with a module and channel number. + * + * @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 (usually + * PWM) + */ + WPI_DEPRECATED("use SendableRegistry::SetName()") + void SetName(const wpi::Twine& moduleType, int moduleNumber, int channel) { + SendableRegistry::GetInstance().SetName(static_cast(this), + moduleType, moduleNumber, channel); + } + + protected: + SendableHelper() = default; + + ~SendableHelper() { + // it is safe to call Remove() multiple times with the same object + SendableRegistry::GetInstance().Remove(static_cast(this)); + } +}; + +} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableRegistry.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableRegistry.h new file mode 100644 index 0000000000..2628f4fbad --- /dev/null +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableRegistry.h @@ -0,0 +1,277 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +#pragma once + +#include +#include + +#include +#include + +namespace frc { + +class Sendable; + +/** + * The SendableRegistry class is the public interface for registering sensors + * and actuators for use on dashboards and LiveWindow. + */ +class SendableRegistry { + public: + SendableRegistry(const SendableRegistry&) = delete; + SendableRegistry& operator=(const SendableRegistry&) = delete; + + /** + * Gets an instance of the SendableRegistry class. + * + * This is a singleton to guarantee that there is only a single instance + * regardless of how many times GetInstance is called. + */ + static SendableRegistry& GetInstance(); + + /** + * Adds an object to the registry. + * + * @param sendable object to add + * @param name component name + */ + void Add(Sendable* sendable, const wpi::Twine& name); + + /** + * Adds an object to the registry. + * + * @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 + */ + void Add(Sendable* sendable, const wpi::Twine& moduleType, int channel); + + /** + * Adds an object to the registry. + * + * @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 + */ + void Add(Sendable* sendable, const wpi::Twine& moduleType, int moduleNumber, + int channel); + + /** + * Adds an object to the registry. + * + * @param sendable object to add + * @param subsystem subsystem name + * @param name component name + */ + void Add(Sendable* sendable, const wpi::Twine& subsystem, + const wpi::Twine& name); + + /** + * Adds an object to the registry and LiveWindow. + * + * @param sendable object to add + * @param name component name + */ + void AddLW(Sendable* sendable, const wpi::Twine& 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 + */ + void AddLW(Sendable* sendable, const wpi::Twine& 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 + */ + void AddLW(Sendable* sendable, const wpi::Twine& 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 + */ + void AddLW(Sendable* sendable, const wpi::Twine& subsystem, + const wpi::Twine& name); + + /** + * Adds a child object to an object. Adds the child object to the registry + * if it's not already present. + * + * @param parent parent object + * @param child child object + */ + void AddChild(Sendable* parent, void* child); + + /** + * Removes an object from the registry. + * + * @param sendable object to remove + * @return true if the object was removed; false if it was not present + */ + bool Remove(Sendable* sendable); + + /** + * Moves an object in the registry (for use in move constructors/assignments). + * + * @param to new object + * @param from old object + */ + void Move(Sendable* to, Sendable* from); + + /** + * Determines if an object is in the registry. + * + * @param sendable object to check + * @return True if in registry, false if not. + */ + bool Contains(const Sendable* sendable) const; + + /** + * Gets the name of an object. + * + * @param sendable object + * @return Name (empty if object is not in registry) + */ + std::string GetName(const Sendable* sendable) const; + + /** + * Sets the name of an object. + * + * @param sendable object + * @param name name + */ + void SetName(Sendable* sendable, const wpi::Twine& name); + + /** + * Sets the name of an object with a channel number. + * + * @param sendable object + * @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 + */ + void SetName(Sendable* sendable, const wpi::Twine& moduleType, int channel); + + /** + * Sets the name of an object with a module and channel number. + * + * @param sendable object + * @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 + */ + void SetName(Sendable* sendable, const wpi::Twine& moduleType, + int moduleNumber, int channel); + + /** + * Sets both the subsystem name and device name of an object. + * + * @param sendable object + * @param subsystem subsystem name + * @param name device name + */ + void SetName(Sendable* sendable, const wpi::Twine& subsystem, + const wpi::Twine& name); + + /** + * Gets the subsystem name of an object. + * + * @param sendable object + * @return Subsystem name (empty if object is not in registry) + */ + std::string GetSubsystem(const Sendable* sendable) const; + + /** + * Sets the subsystem name of an object. + * + * @param sendable object + * @param subsystem subsystem name + */ + void SetSubsystem(Sendable* sendable, const wpi::Twine& subsystem); + + /** + * Gets a unique handle for setting/getting data with SetData() and GetData(). + * + * @return Handle + */ + int GetDataHandle(); + + /** + * Associates arbitrary data with an object in the registry. + * + * @param sendable object + * @param handle data handle returned by GetDataHandle() + * @param data data to set + * @return Previous data (may be null) + */ + std::shared_ptr SetData(Sendable* sendable, int handle, + std::shared_ptr data); + + /** + * Gets arbitrary data associated with an object in the registry. + * + * @param sendable object + * @param handle data handle returned by GetDataHandle() + * @return data (may be null if none associated) + */ + std::shared_ptr GetData(Sendable* sendable, int handle); + + /** + * Enables LiveWindow for an object. + * + * @param sendable object + */ + void EnableLiveWindow(Sendable* sendable); + + /** + * Disables LiveWindow for an object. + * + * @param sendable object + */ + void DisableLiveWindow(Sendable* sendable); + + /** + * 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 + */ + void ForeachLiveWindow( + int dataHandle, + wpi::function_ref& data)> + callback) const; + + private: + SendableRegistry(); + + struct Impl; + std::unique_ptr m_impl; +}; + +} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h b/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h index a7161da297..97805ba8e6 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h @@ -15,13 +15,14 @@ #include "frc/ErrorBase.h" #include "frc/smartdashboard/ListenerExecutor.h" -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { -class Sendable; - -class SmartDashboard : public ErrorBase, public SendableBase { +class SmartDashboard : public ErrorBase, + public Sendable, + public SendableHelper { public: static void init(); @@ -101,6 +102,9 @@ class SmartDashboard : public ErrorBase, public SendableBase { * The value can be retrieved by calling the get method with a key that is * equal to the original key. * + * In order for the value to appear in the dashboard, it must be registered + * with SendableRegistry. WPILib components do this automatically. + * * @param keyName the key * @param value the value */ @@ -113,6 +117,9 @@ class SmartDashboard : public ErrorBase, public SendableBase { * The value can be retrieved by calling the get method with a key that is * equal to the original key. * + * In order for the value to appear in the dashboard, it must be registered + * with SendableRegistry. WPILib components do this automatically. + * * @param value the value */ static void PutData(Sendable* value); diff --git a/wpilibc/src/main/native/include/frc2/command/Command.h b/wpilibc/src/main/native/include/frc2/command/Command.h index e01f824c57..5fc82f4c7b 100644 --- a/wpilibc/src/main/native/include/frc2/command/Command.h +++ b/wpilibc/src/main/native/include/frc2/command/Command.h @@ -52,9 +52,13 @@ class ProxyScheduleCommand; class Command : public frc::ErrorBase { public: Command() = default; - Command(Command&& other) = default; virtual ~Command(); + Command(const Command&); + Command& operator=(const Command&); + Command(Command&&) = default; + Command& operator=(Command&&) = default; + /** * The initial subroutine of a command. Called once when the command is * initially scheduled. diff --git a/wpilibc/src/main/native/include/frc2/command/CommandBase.h b/wpilibc/src/main/native/include/frc2/command/CommandBase.h index 7597d210a1..3b1698f4fd 100644 --- a/wpilibc/src/main/native/include/frc2/command/CommandBase.h +++ b/wpilibc/src/main/native/include/frc2/command/CommandBase.h @@ -8,11 +8,12 @@ #pragma once #include +#include #include #include -#include +#include #include "Command.h" @@ -20,12 +21,10 @@ namespace frc2 { /** * A Sendable base class for Commands. */ -class CommandBase : public frc::Sendable, public Command { +class CommandBase : public Command, + public frc::Sendable, + public frc::SendableHelper { public: - CommandBase(CommandBase&& other) = default; - - CommandBase(const CommandBase& other); - /** * Adds the specified requirements to the command. * @@ -37,20 +36,38 @@ class CommandBase : public frc::Sendable, public Command { wpi::SmallSet GetRequirements() const override; - void SetName(const wpi::Twine& name) override; + /** + * Sets the name of this Command. + * + * @param name name + */ + void SetName(const wpi::Twine& name); + /** + * Gets the name of this Command. + * + * @return Name + */ std::string GetName() const override; - std::string GetSubsystem() const override; + /** + * Gets the subsystem name of this Command. + * + * @return Subsystem name + */ + std::string GetSubsystem() const; - void SetSubsystem(const wpi::Twine& subsystem) override; + /** + * Sets the subsystem name of this Command. + * + * @param subsystem subsystem name + */ + void SetSubsystem(const wpi::Twine& subsystem); void InitSendable(frc::SendableBuilder& builder) override; protected: CommandBase(); - std::string m_name; - std::string m_subsystem; wpi::SmallSet m_requirements; }; } // namespace frc2 diff --git a/wpilibc/src/main/native/include/frc2/command/CommandScheduler.h b/wpilibc/src/main/native/include/frc2/command/CommandScheduler.h index 92dffc7d56..9f1d81a684 100644 --- a/wpilibc/src/main/native/include/frc2/command/CommandScheduler.h +++ b/wpilibc/src/main/native/include/frc2/command/CommandScheduler.h @@ -10,7 +10,8 @@ #include #include #include -#include +#include +#include #include #include @@ -34,7 +35,9 @@ class Subsystem; * with the scheduler using RegisterSubsystem() in order for their Periodic() * methods to be called and for their default commands to be scheduled. */ -class CommandScheduler final : public frc::SendableBase, frc::ErrorBase { +class CommandScheduler final : public frc::Sendable, + public frc::ErrorBase, + public frc::SendableHelper { public: /** * Returns the Scheduler instance. diff --git a/wpilibc/src/main/native/include/frc2/command/SubsystemBase.h b/wpilibc/src/main/native/include/frc2/command/SubsystemBase.h index 2546f5bfab..e7dffc7d27 100644 --- a/wpilibc/src/main/native/include/frc2/command/SubsystemBase.h +++ b/wpilibc/src/main/native/include/frc2/command/SubsystemBase.h @@ -8,6 +8,7 @@ #pragma once #include +#include #include @@ -18,17 +19,50 @@ namespace frc2 { * A base for subsystems that handles registration in the constructor, and * provides a more intuitive method for setting the default command. */ -class SubsystemBase : public Subsystem, public frc::Sendable { +class SubsystemBase : public Subsystem, + public frc::Sendable, + public frc::SendableHelper { public: void InitSendable(frc::SendableBuilder& builder) override; - std::string GetName() const override; - void SetName(const wpi::Twine& name) override; - std::string GetSubsystem() const override; - void SetSubsystem(const wpi::Twine& name) override; + + /** + * Gets the name of this Subsystem. + * + * @return Name + */ + std::string GetName() const; + + /** + * Sets the name of this Subsystem. + * + * @param name name + */ + void SetName(const wpi::Twine& name); + + /** + * Gets the subsystem name of this Subsystem. + * + * @return Subsystem name + */ + std::string GetSubsystem() const; + + /** + * Sets the subsystem name of this Subsystem. + * + * @param subsystem subsystem name + */ + void SetSubsystem(const wpi::Twine& name); + + /** + * Associate a Sendable with this Subsystem. + * Also update the child's name. + * + * @param name name to give child + * @param child sendable + */ void AddChild(std::string name, frc::Sendable* child); protected: SubsystemBase(); - std::string m_name; }; } // namespace frc2 diff --git a/wpilibc/src/test/native/cpp/shuffleboard/MockActuatorSendable.cpp b/wpilibc/src/test/native/cpp/shuffleboard/MockActuatorSendable.cpp index 3c9e411fd6..172d7c6310 100644 --- a/wpilibc/src/test/native/cpp/shuffleboard/MockActuatorSendable.cpp +++ b/wpilibc/src/test/native/cpp/shuffleboard/MockActuatorSendable.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -7,11 +7,12 @@ #include "shuffleboard/MockActuatorSendable.h" +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; -MockActuatorSendable::MockActuatorSendable(wpi::StringRef name) - : SendableBase(false) { - SetName(name); +MockActuatorSendable::MockActuatorSendable(wpi::StringRef name) { + SendableRegistry::GetInstance().Add(this, name); } void MockActuatorSendable::InitSendable(SendableBuilder& builder) { diff --git a/wpilibc/src/test/native/include/shuffleboard/MockActuatorSendable.h b/wpilibc/src/test/native/include/shuffleboard/MockActuatorSendable.h index f56215c42e..1cba8e30ba 100644 --- a/wpilibc/src/test/native/include/shuffleboard/MockActuatorSendable.h +++ b/wpilibc/src/test/native/include/shuffleboard/MockActuatorSendable.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,15 +9,17 @@ #include -#include "frc/smartdashboard/SendableBase.h" +#include "frc/smartdashboard/Sendable.h" #include "frc/smartdashboard/SendableBuilder.h" +#include "frc/smartdashboard/SendableHelper.h" namespace frc { /** * A mock sendable that marks itself as an actuator. */ -class MockActuatorSendable : public SendableBase { +class MockActuatorSendable : public Sendable, + public SendableHelper { public: explicit MockActuatorSendable(wpi::StringRef name); diff --git a/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/MockActuatorSendable.cpp b/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/MockActuatorSendable.cpp index 3c9e411fd6..172d7c6310 100644 --- a/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/MockActuatorSendable.cpp +++ b/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/MockActuatorSendable.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -7,11 +7,12 @@ #include "shuffleboard/MockActuatorSendable.h" +#include "frc/smartdashboard/SendableRegistry.h" + using namespace frc; -MockActuatorSendable::MockActuatorSendable(wpi::StringRef name) - : SendableBase(false) { - SetName(name); +MockActuatorSendable::MockActuatorSendable(wpi::StringRef name) { + SendableRegistry::GetInstance().Add(this, name); } void MockActuatorSendable::InitSendable(SendableBuilder& builder) { 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 e91b8d2859..e994105e7f 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 @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -16,12 +16,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.wpilibj.interfaces.Accelerometer; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * ADXL345 I2C Accelerometer. */ @SuppressWarnings({"TypeName", "PMD.UnusedPrivateField"}) -public class ADXL345_I2C extends SendableBase implements Accelerometer { +public class ADXL345_I2C implements Accelerometer, Sendable, AutoCloseable { private static final byte kAddress = 0x1D; private static final byte kPowerCtlRegister = 0x2D; private static final byte kDataFormatRegister = 0x31; @@ -89,12 +90,11 @@ public class ADXL345_I2C extends SendableBase implements Accelerometer { setRange(range); HAL.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C); - setName("ADXL345_I2C", port.value); + SendableRegistry.addLW(this, "ADXL345_I2C", port.value); } @Override public void close() { - super.close(); m_i2c.close(); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java index b5d3618fa1..030670761b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -16,12 +16,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.wpilibj.interfaces.Accelerometer; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * ADXL345 SPI Accelerometer. */ @SuppressWarnings({"TypeName", "PMD.UnusedPrivateField"}) -public class ADXL345_SPI extends SendableBase implements Accelerometer { +public class ADXL345_SPI implements Accelerometer, Sendable, AutoCloseable { private static final int kPowerCtlRegister = 0x2D; private static final int kDataFormatRegister = 0x31; private static final int kDataRegister = 0x32; @@ -75,12 +76,11 @@ public class ADXL345_SPI extends SendableBase implements Accelerometer { public ADXL345_SPI(SPI.Port port, Range range) { m_spi = new SPI(port); init(range); - setName("ADXL345_SPI", port.value); + SendableRegistry.addLW(this, "ADXL345_SPI", port.value); } @Override public void close() { - super.close(); m_spi.close(); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java index 5324b63ef3..2b675b447b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -15,6 +15,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.wpilibj.interfaces.Accelerometer; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * ADXL362 SPI Accelerometer. @@ -22,7 +23,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; *

This class allows access to an Analog Devices ADXL362 3-axis accelerometer. */ @SuppressWarnings("PMD.UnusedPrivateField") -public class ADXL362 extends SendableBase implements Accelerometer { +public class ADXL362 implements Accelerometer, Sendable, AutoCloseable { private static final byte kRegWrite = 0x0A; private static final byte kRegRead = 0x0B; @@ -108,12 +109,11 @@ public class ADXL362 extends SendableBase implements Accelerometer { m_spi.write(transferBuffer, 3); HAL.report(tResourceType.kResourceType_ADXL362, port.value); - setName("ADXL362", port.value); + SendableRegistry.addLW(this, "ADXL362", port.value); } @Override public void close() { - super.close(); if (m_spi != null) { m_spi.close(); m_spi = null; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java index a34b373953..a167a51b15 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2015-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2015-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -13,6 +13,7 @@ import java.nio.ByteOrder; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.interfaces.Gyro; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Use a rate gyro to return the robots heading relative to a starting position. The Gyro class @@ -24,7 +25,7 @@ import edu.wpi.first.wpilibj.interfaces.Gyro; *

This class is for the digital ADXRS450 gyro sensor that connects via SPI. */ @SuppressWarnings({"TypeName", "AbbreviationAsWordInName", "PMD.UnusedPrivateField"}) -public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, Sendable { +public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, Sendable, AutoCloseable { private static final double kSamplePeriod = 0.0005; private static final double kCalibrationSampleTime = 5.0; private static final double kDegreePerSecondPerLSB = 0.0125; @@ -77,7 +78,7 @@ public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, Sendable calibrate(); HAL.report(tResourceType.kResourceType_ADXRS450, port.value); - setName("ADXRS450_Gyro", port.value); + SendableRegistry.addLW(this, "ADXRS450_Gyro", port.value); } public boolean isConnected() { @@ -142,7 +143,6 @@ public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, Sendable */ @Override public void close() { - super.close(); if (m_spi != null) { m_spi.close(); m_spi = null; 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 abd3cdcf0a..b4fc0e4ed6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java @@ -10,6 +10,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; @@ -18,7 +19,7 @@ import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; * through the sensor. Many sensors have multiple axis and can be treated as multiple devices. Each * is calibrated by finding the center value over a period of time. */ -public class AnalogAccelerometer extends SendableBase implements PIDSource { +public class AnalogAccelerometer implements PIDSource, Sendable, AutoCloseable { private AnalogInput m_analogChannel; private double m_voltsPerG = 1.0; private double m_zeroGVoltage = 2.5; @@ -31,7 +32,7 @@ public class AnalogAccelerometer extends SendableBase implements PIDSource { private void initAccelerometer() { HAL.report(tResourceType.kResourceType_Accelerometer, m_analogChannel.getChannel()); - setName("Accelerometer", m_analogChannel.getChannel()); + SendableRegistry.addLW(this, "Accelerometer", m_analogChannel.getChannel()); } /** @@ -43,7 +44,7 @@ public class AnalogAccelerometer extends SendableBase implements PIDSource { */ public AnalogAccelerometer(final int channel) { this(new AnalogInput(channel), true); - addChild(m_analogChannel); + SendableRegistry.addChild(this, m_analogChannel); } /** @@ -70,7 +71,6 @@ public class AnalogAccelerometer extends SendableBase implements PIDSource { */ @Override public void close() { - super.close(); if (m_analogChannel != null && m_allocatedChannel) { m_analogChannel.close(); } 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 259adf1b3d..a06bae0249 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java @@ -11,6 +11,7 @@ import edu.wpi.first.hal.AnalogGyroJNI; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.interfaces.Gyro; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; @@ -23,7 +24,7 @@ import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; * *

This class is for gyro sensors that connect to an analog input. */ -public class AnalogGyro extends GyroBase implements Gyro, PIDSource, Sendable { +public class AnalogGyro extends GyroBase implements Gyro, PIDSource, Sendable, AutoCloseable { private static final double kDefaultVoltsPerDegreePerSecond = 0.007; protected AnalogInput m_analog; private boolean m_channelAllocated; @@ -41,7 +42,7 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, Sendable { AnalogGyroJNI.setupAnalogGyro(m_gyroHandle); HAL.report(tResourceType.kResourceType_Gyro, m_analog.getChannel()); - setName("AnalogGyro", m_analog.getChannel()); + SendableRegistry.addLW(this, "AnalogGyro", m_analog.getChannel()); } @Override @@ -58,7 +59,7 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, Sendable { public AnalogGyro(int channel) { this(new AnalogInput(channel)); m_channelAllocated = true; - addChild(m_analog); + SendableRegistry.addChild(this, m_analog); } /** @@ -88,7 +89,7 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, Sendable { public AnalogGyro(int channel, int center, double offset) { this(new AnalogInput(channel), center, offset); m_channelAllocated = true; - addChild(m_analog); + SendableRegistry.addChild(this, m_analog); } /** @@ -120,7 +121,6 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, Sendable { */ @Override public void close() { - super.close(); if (m_analog != null && m_channelAllocated) { m_analog.close(); } 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 74eb866b9b..32e951bf3b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -14,6 +14,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.sim.AnalogInSim; import edu.wpi.first.hal.util.AllocationException; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Analog channel class. @@ -27,7 +28,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; * accumulated effectively increasing the resolution, while the averaged samples are divided by the * number of samples to retain the resolution, but get more stable values. */ -public class AnalogInput extends SendableBase implements PIDSource { +public class AnalogInput implements PIDSource, Sendable, AutoCloseable { private static final int kAccumulatorSlot = 1; int m_port; // explicit no modifier, private and package accessible. private int m_channel; @@ -48,12 +49,11 @@ public class AnalogInput extends SendableBase implements PIDSource { m_port = AnalogJNI.initializeAnalogInputPort(portHandle); HAL.report(tResourceType.kResourceType_AnalogChannel, channel); - setName("AnalogInput", channel); + SendableRegistry.addLW(this, "AnalogInput", channel); } @Override public void close() { - super.close(); AnalogJNI.freeAnalogInputPort(m_port); m_port = 0; m_channel = 0; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java index ff81e9ea58..35202b5653 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,11 +12,12 @@ import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.sim.AnalogOutSim; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Analog output class. */ -public class AnalogOutput extends SendableBase { +public class AnalogOutput implements Sendable, AutoCloseable { private int m_port; private int m_channel; @@ -33,12 +34,11 @@ public class AnalogOutput extends SendableBase { m_port = AnalogJNI.initializeAnalogOutputPort(portHandle); HAL.report(tResourceType.kResourceType_AnalogOutput, channel); - setName("AnalogOutput", channel); + SendableRegistry.addLW(this, "AnalogOutput", channel); } @Override public void close() { - super.close(); AnalogJNI.freeAnalogOutputPort(m_port); m_port = 0; m_channel = 0; 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 d1a9018a2c..57239ca31f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,13 +9,14 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.wpilibj.interfaces.Potentiometer; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Class for reading analog potentiometers. Analog potentiometers read in an analog voltage that * corresponds to a position. The position is in whichever units you choose, by way of the scaling * and offset constants passed to the constructor. */ -public class AnalogPotentiometer extends SendableBase implements Potentiometer { +public class AnalogPotentiometer implements Potentiometer, Sendable, AutoCloseable { private AnalogInput m_analogInput; private boolean m_initAnalogInput; private double m_fullRange; @@ -38,7 +39,7 @@ public class AnalogPotentiometer extends SendableBase implements Potentiometer { public AnalogPotentiometer(final int channel, double fullRange, double offset) { this(new AnalogInput(channel), fullRange, offset); m_initAnalogInput = true; - addChild(m_analogInput); + SendableRegistry.addChild(this, m_analogInput); } /** @@ -55,7 +56,7 @@ public class AnalogPotentiometer extends SendableBase implements Potentiometer { * @param offset The offset to add to the scaled value for controlling the zero value */ public AnalogPotentiometer(final AnalogInput input, double fullRange, double offset) { - setName("AnalogPotentiometer", input.getChannel()); + SendableRegistry.addLW(this, "AnalogPotentiometer", input.getChannel()); m_analogInput = input; m_initAnalogInput = false; @@ -156,7 +157,6 @@ public class AnalogPotentiometer extends SendableBase implements Potentiometer { @Override public void close() { - super.close(); if (m_initAnalogInput) { m_analogInput.close(); m_analogInput = null; 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 e429246754..c0de21168b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -16,12 +16,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.util.BoundaryException; import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Class for creating and configuring Analog Triggers. */ -public class AnalogTrigger extends SendableBase { +public class AnalogTrigger implements Sendable, AutoCloseable { /** * Exceptions dealing with improper operation of the Analog trigger. */ @@ -53,7 +54,7 @@ public class AnalogTrigger extends SendableBase { public AnalogTrigger(final int channel) { this(new AnalogInput(channel)); m_ownsAnalog = true; - addChild(m_analogInput); + SendableRegistry.addChild(this, m_analogInput); } /** @@ -72,12 +73,11 @@ public class AnalogTrigger extends SendableBase { m_index = index.asIntBuffer().get(0); HAL.report(tResourceType.kResourceType_AnalogTrigger, channel.getChannel()); - setName("AnalogTrigger", channel.getChannel()); + SendableRegistry.addLW(this, "AnalogTrigger", channel.getChannel()); } @Override public void close() { - super.close(); AnalogJNI.cleanAnalogTrigger(m_port); m_port = 0; if (m_ownsAnalog && m_analogInput != null) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java index 4785c2e601..049beb3739 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java @@ -40,7 +40,7 @@ import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; * the averaging engine may help with this, but rotational speeds of the sensor will then be * limited. */ -public class AnalogTriggerOutput extends DigitalSource { +public class AnalogTriggerOutput extends DigitalSource implements Sendable { /** * Exceptions dealing with improper operation of the Analog trigger output. */ diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java index d8dbafe3bc..e7a24f9f68 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -13,13 +13,14 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.sim.AccelerometerSim; import edu.wpi.first.wpilibj.interfaces.Accelerometer; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Built-in accelerometer. * *

This class allows access to the roboRIO's internal accelerometer. */ -public class BuiltInAccelerometer extends SendableBase implements Accelerometer { +public class BuiltInAccelerometer implements Accelerometer, Sendable { /** * Constructor. * @@ -28,7 +29,7 @@ public class BuiltInAccelerometer extends SendableBase implements Accelerometer public BuiltInAccelerometer(Range range) { setRange(range); HAL.report(tResourceType.kResourceType_Accelerometer, 0, 0, "Built-in accelerometer"); - setName("BuiltInAccel", 0); + SendableRegistry.addLW(this, "BuiltInAccel", 0); } /** 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 e95e8a7360..66cd9aa9af 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,6 +11,7 @@ import edu.wpi.first.hal.CompressorJNI; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Class for operating a compressor connected to a PCM (Pneumatic Control Module). The PCM will @@ -23,7 +24,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; * the safety provided by using the pressure switch and closed loop control. You can only turn off * closed loop control, thereby stopping the compressor from operating. */ -public class Compressor extends SendableBase { +public class Compressor implements Sendable { private int m_compressorHandle; private byte m_module; @@ -39,7 +40,7 @@ public class Compressor extends SendableBase { m_compressorHandle = CompressorJNI.initializeCompressor((byte) module); HAL.report(tResourceType.kResourceType_Compressor, module); - setName("Compressor", module); + SendableRegistry.addLW(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 73ad85238d..65e636ccba 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java @@ -15,6 +15,7 @@ import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; import static java.util.Objects.requireNonNull; @@ -29,7 +30,7 @@ import static java.util.Objects.requireNonNull; *

All counters will immediately start counting - reset() them if you need them to be zeroed * before use. */ -public class Counter extends SendableBase implements CounterBase, PIDSource { +public class Counter implements CounterBase, PIDSource, Sendable, AutoCloseable { /** * Mode determines how and what the counter counts. */ @@ -86,7 +87,7 @@ public class Counter extends SendableBase implements CounterBase, PIDSource { setMaxPeriod(.5); HAL.report(tResourceType.kResourceType_Counter, m_index, mode.value); - setName("Counter", m_index); + SendableRegistry.addLW(this, "Counter", m_index); } /** @@ -182,7 +183,6 @@ public class Counter extends SendableBase implements CounterBase, PIDSource { @Override public void close() { - super.close(); setUpdateWhenEmpty(true); clearUpSource(); @@ -213,7 +213,7 @@ public class Counter extends SendableBase implements CounterBase, PIDSource { public void setUpSource(int channel) { setUpSource(new DigitalInput(channel)); m_allocatedUpSource = true; - addChild(m_upSource); + SendableRegistry.addChild(this, m_upSource); } /** @@ -280,7 +280,7 @@ public class Counter extends SendableBase implements CounterBase, PIDSource { public void setDownSource(int channel) { setDownSource(new DigitalInput(channel)); m_allocatedDownSource = true; - addChild(m_downSource); + SendableRegistry.addChild(this, m_downSource); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMC60.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMC60.java index c2f4c9cdcd..f414773ba7 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMC60.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMC60.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Digilent DMC 60 Speed Controller. @@ -39,6 +40,6 @@ public class DMC60 extends PWMSpeedController { setZeroLatch(); HAL.report(tResourceType.kResourceType_DigilentDMC60, getChannel()); - setName("DMC60", getChannel()); + SendableRegistry.setName(this, "DMC60", getChannel()); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java index ad92f48a3b..d90fc51843 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2015-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2015-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -14,13 +14,14 @@ import edu.wpi.first.hal.DigitalGlitchFilterJNI; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Class to enable glitch filtering on a set of digital inputs. This class will manage adding and * removing digital inputs from a FPGA glitch filter. The filter lets the user configure the time * that an input must remain high or low before it is classified as high or low. */ -public class DigitalGlitchFilter extends SendableBase { +public class DigitalGlitchFilter implements Sendable, AutoCloseable { /** * Configures the Digital Glitch Filter to its default settings. */ @@ -35,14 +36,13 @@ public class DigitalGlitchFilter extends SendableBase { m_filterAllocated[index] = true; HAL.report(tResourceType.kResourceType_DigitalGlitchFilter, m_channelIndex, 0); - setName("DigitalGlitchFilter", index); + SendableRegistry.addLW(this, "DigitalGlitchFilter", index); } } } @Override public void close() { - super.close(); if (m_channelIndex >= 0) { synchronized (m_mutex) { m_filterAllocated[m_channelIndex] = false; 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 03a0f21351..3e28b8cd08 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,6 +11,7 @@ import edu.wpi.first.hal.DIOJNI; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Class to read a digital input. This class will read digital inputs and return the current value @@ -18,7 +19,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; * elsewhere will automatically allocate digital inputs and outputs as required. This class is only * for devices like switches etc. that aren't implemented anywhere else. */ -public class DigitalInput extends DigitalSource { +public class DigitalInput extends DigitalSource implements Sendable, AutoCloseable { private final int m_channel; private int m_handle; @@ -34,7 +35,7 @@ public class DigitalInput extends DigitalSource { m_handle = DIOJNI.initializeDIOPort(HAL.getPort((byte) channel), true); HAL.report(tResourceType.kResourceType_DigitalInput, channel); - setName("DigitalInput", channel); + SendableRegistry.addLW(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 f375ccb76e..37b134770a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,12 +11,13 @@ import edu.wpi.first.hal.DIOJNI; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Class to write digital outputs. This class will write digital outputs. Other devices that are * implemented elsewhere will automatically allocate digital inputs and outputs as required. */ -public class DigitalOutput extends SendableBase { +public class DigitalOutput implements Sendable, AutoCloseable { private static final int invalidPwmGenerator = 0; private int m_pwmGenerator = invalidPwmGenerator; @@ -37,12 +38,11 @@ public class DigitalOutput extends SendableBase { m_handle = DIOJNI.initializeDIOPort(HAL.getPort((byte) channel), false); HAL.report(tResourceType.kResourceType_DigitalOutput, channel); - setName("DigitalOutput", channel); + SendableRegistry.addLW(this, "DigitalOutput", channel); } @Override public void close() { - super.close(); // Disable the pwm only if we have allocated it if (m_pwmGenerator != invalidPwmGenerator) { disablePWM(); 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 8cd60ec476..b4bb97e867 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,6 +12,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.SolenoidJNI; import edu.wpi.first.hal.util.UncleanStatusException; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * DoubleSolenoid class for running 2 channels of high voltage Digital Output on the PCM. @@ -19,7 +20,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; *

The DoubleSolenoid class is typically used for pneumatics solenoids that have two positions * controlled by two separate channels. */ -public class DoubleSolenoid extends SolenoidBase { +public class DoubleSolenoid extends SolenoidBase implements Sendable, AutoCloseable { /** * Possible values for a DoubleSolenoid. */ @@ -80,12 +81,11 @@ public class DoubleSolenoid extends SolenoidBase { m_moduleNumber); HAL.report(tResourceType.kResourceType_Solenoid, reverseChannel, m_moduleNumber); - setName("DoubleSolenoid", m_moduleNumber, forwardChannel); + SendableRegistry.addLW(this, "DoubleSolenoid", m_moduleNumber, forwardChannel); } @Override public synchronized void close() { - super.close(); SolenoidJNI.freeSolenoidPort(m_forwardHandle); SolenoidJNI.freeSolenoidPort(m_reverseHandle); } 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 6425e0dfcf..396239882e 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java @@ -12,6 +12,7 @@ import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.util.AllocationException; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; @@ -28,7 +29,7 @@ import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; *

All encoders will immediately start counting - reset() them if you need them to be zeroed * before use. */ -public class Encoder extends SendableBase implements CounterBase, PIDSource { +public class Encoder implements CounterBase, PIDSource, Sendable, AutoCloseable { public enum IndexingType { kResetWhileHigh(0), kResetWhileLow(1), kResetOnFallingEdge(2), kResetOnRisingEdge(3); @@ -79,7 +80,7 @@ public class Encoder extends SendableBase implements CounterBase, PIDSource { int fpgaIndex = getFPGAIndex(); HAL.report(tResourceType.kResourceType_Encoder, fpgaIndex, type.value); - setName("Encoder", fpgaIndex); + SendableRegistry.addLW(this, "Encoder", fpgaIndex); } /** @@ -133,8 +134,8 @@ public class Encoder extends SendableBase implements CounterBase, PIDSource { m_allocatedI = false; m_aSource = new DigitalInput(channelA); m_bSource = new DigitalInput(channelB); - addChild(m_aSource); - addChild(m_bSource); + SendableRegistry.addChild(this, m_aSource); + SendableRegistry.addChild(this, m_bSource); initEncoder(reverseDirection, encodingType); } @@ -155,7 +156,7 @@ public class Encoder extends SendableBase implements CounterBase, PIDSource { this(channelA, channelB, reverseDirection); m_allocatedI = true; m_indexSource = new DigitalInput(indexChannel); - addChild(m_indexSource); + SendableRegistry.addChild(this, m_indexSource); setIndexSource(m_indexSource); } @@ -292,7 +293,6 @@ public class Encoder extends SendableBase implements CounterBase, PIDSource { @Override public void close() { - super.close(); if (m_aSource != null && m_allocatedA) { m_aSource.close(); m_allocatedA = false; @@ -544,7 +544,7 @@ public class Encoder extends SendableBase implements CounterBase, PIDSource { } m_indexSource = new DigitalInput(channel); m_allocatedI = true; - addChild(m_indexSource); + SendableRegistry.addChild(this, m_indexSource); setIndexSource(m_indexSource, type); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/GearTooth.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/GearTooth.java index b156ec38f8..80b58045c5 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/GearTooth.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/GearTooth.java @@ -10,6 +10,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Alias for counter class. Implement the gear tooth sensor supplied by FIRST. Currently there is no @@ -59,7 +60,7 @@ public class GearTooth extends Counter { } else { HAL.report(tResourceType.kResourceType_GearTooth, channel, 0); } - setName("GearTooth", channel); + SendableRegistry.setName(this, "GearTooth", channel); } /** @@ -78,7 +79,7 @@ public class GearTooth extends Counter { } else { HAL.report(tResourceType.kResourceType_GearTooth, source.getChannel(), 0); } - setName("GearTooth", source.getChannel()); + SendableRegistry.setName(this, "GearTooth", source.getChannel()); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/GyroBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/GyroBase.java index 4bd47e82f0..21330ce5ae 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/GyroBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/GyroBase.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -13,7 +13,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; /** * GyroBase is the common base class for Gyro implementations such as AnalogGyro. */ -public abstract class GyroBase extends SendableBase implements Gyro, PIDSource { +public abstract class GyroBase implements Gyro, PIDSource, Sendable { private PIDSourceType m_pidSource = PIDSourceType.kDisplacement; /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java index 52e1571d3b..bd21d24b0e 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java @@ -17,7 +17,7 @@ import edu.wpi.first.hal.util.AllocationException; * Base for sensors to be used with interrupts. */ @SuppressWarnings("PMD.TooManyMethods") -public abstract class InterruptableSensorBase extends SendableBase { +public abstract class InterruptableSensorBase implements AutoCloseable { @SuppressWarnings("JavadocMethod") public enum WaitResult { kTimeout(0x0), kRisingEdge(0x1), kFallingEdge(0x100), kBoth(0x101); @@ -61,7 +61,6 @@ public abstract class InterruptableSensorBase extends SendableBase { @Override public void close() { - super.close(); if (m_interrupt != 0) { cancelInterrupts(); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Jaguar.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Jaguar.java index 934e70b6a1..b863f2eaa0 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Jaguar.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Jaguar.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Texas Instruments / Vex Robotics Jaguar Speed Controller as a PWM device. @@ -37,6 +38,6 @@ public class Jaguar extends PWMSpeedController { setZeroLatch(); HAL.report(tResourceType.kResourceType_Jaguar, getChannel()); - setName("Jaguar", getChannel()); + SendableRegistry.setName(this, "Jaguar", getChannel()); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java index f166b46dec..06f50f5c02 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,6 +10,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Nidec Brushless Motor. @@ -22,8 +23,6 @@ public class NidecBrushless extends MotorSafety implements SpeedController, Send private volatile double m_speed; private volatile boolean m_disabled; - private final SendableImpl m_sendableImpl; - /** * Constructor. * @@ -33,81 +32,28 @@ public class NidecBrushless extends MotorSafety implements SpeedController, Send * 0-9 are on-board, 10-25 are on the MXP port */ public NidecBrushless(final int pwmChannel, final int dioChannel) { - m_sendableImpl = new SendableImpl(true); - setSafetyEnabled(false); // the dio controls the output (in PWM mode) m_dio = new DigitalOutput(dioChannel); - addChild(m_dio); + SendableRegistry.addChild(this, m_dio); m_dio.setPWMRate(15625); m_dio.enablePWM(0.5); // the pwm enables the controller m_pwm = new PWM(pwmChannel); - addChild(m_pwm); + SendableRegistry.addChild(this, m_pwm); HAL.report(tResourceType.kResourceType_NidecBrushless, pwmChannel); - setName("Nidec Brushless", pwmChannel); + SendableRegistry.addLW(this, "Nidec Brushless", pwmChannel); } @Override public void close() { - m_sendableImpl.close(); m_dio.close(); m_pwm.close(); } - @Override - public final synchronized String getName() { - return m_sendableImpl.getName(); - } - - @Override - public final synchronized void setName(String name) { - m_sendableImpl.setName(name); - } - - /** - * Sets the name of the sensor with a channel number. - * - * @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 - */ - protected final void setName(String moduleType, int channel) { - m_sendableImpl.setName(moduleType, channel); - } - - /** - * Sets the name of the sensor with a module and channel number. - * - * @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 (usually PWM) - */ - protected final void setName(String moduleType, int moduleNumber, int channel) { - m_sendableImpl.setName(moduleType, moduleNumber, channel); - } - - @Override - public final synchronized String getSubsystem() { - return m_sendableImpl.getSubsystem(); - } - - @Override - public final synchronized void setSubsystem(String subsystem) { - m_sendableImpl.setSubsystem(subsystem); - } - - /** - * Add a child component. - * - * @param child child component - */ - protected final void addChild(Object child) { - m_sendableImpl.addChild(child); - } - /** * Set the PWM value. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java index 974d5c40b5..702636ca34 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java @@ -13,6 +13,7 @@ import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.util.BoundaryException; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; @@ -27,7 +28,7 @@ import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; * given set of PID constants. */ @SuppressWarnings("PMD.TooManyFields") -public class PIDBase extends SendableBase implements PIDInterface, PIDOutput { +public class PIDBase implements PIDInterface, PIDOutput, Sendable { public static final double kDefaultPeriod = 0.05; private static int instances; @@ -154,7 +155,6 @@ public class PIDBase extends SendableBase implements PIDInterface, PIDOutput { @SuppressWarnings("ParameterName") public PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output) { - super(false); requireNonNullParam(source, "PIDSource", "PIDBase"); requireNonNullParam(output, "output", "PIDBase"); @@ -174,7 +174,7 @@ public class PIDBase extends SendableBase implements PIDInterface, PIDOutput { instances++; HAL.report(tResourceType.kResourceType_PIDController, instances); m_tolerance = new NullTolerance(); - setName("PIDController", instances); + SendableRegistry.add(this, "PIDController", instances); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDController.java index b87e406e1a..881723ef48 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDController.java @@ -22,7 +22,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; * @deprecated Use {@link edu.wpi.first.wpilibj.controller.PIDController} instead. */ @Deprecated(since = "2020", forRemoval = true) -public class PIDController extends PIDBase implements Controller { +public class PIDController extends PIDBase implements Controller, AutoCloseable { Notifier m_controlLoop = new Notifier(this::calculate); /** @@ -97,7 +97,6 @@ public class PIDController extends PIDBase implements Controller { @Override public void close() { - super.close(); m_controlLoop.close(); m_thisMutex.lock(); try { 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 d59a413cf4..9698e1876a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,6 +12,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.PWMConfigDataResult; import edu.wpi.first.hal.PWMJNI; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Class implements the PWM generation in the FPGA. @@ -47,16 +48,12 @@ public class PWM extends MotorSafety implements Sendable, AutoCloseable { private final int m_channel; private int m_handle; - private final SendableImpl m_sendableImpl; - /** * Allocate a PWM given a channel. * * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port */ public PWM(final int channel) { - m_sendableImpl = new SendableImpl(true); - SensorUtil.checkPWMChannel(channel); m_channel = channel; @@ -67,7 +64,7 @@ public class PWM extends MotorSafety implements Sendable, AutoCloseable { PWMJNI.setPWMEliminateDeadband(m_handle, false); HAL.report(tResourceType.kResourceType_PWM, channel); - setName("PWM", channel); + SendableRegistry.addLW(this, "PWM", channel); setSafetyEnabled(false); } @@ -77,8 +74,6 @@ public class PWM extends MotorSafety implements Sendable, AutoCloseable { */ @Override public void close() { - m_sendableImpl.close(); - if (m_handle == 0) { return; } @@ -87,56 +82,6 @@ public class PWM extends MotorSafety implements Sendable, AutoCloseable { m_handle = 0; } - @Override - public final synchronized String getName() { - return m_sendableImpl.getName(); - } - - @Override - public final synchronized void setName(String name) { - m_sendableImpl.setName(name); - } - - /** - * Sets the name of the sensor with a channel number. - * - * @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 - */ - protected final void setName(String moduleType, int channel) { - m_sendableImpl.setName(moduleType, channel); - } - - /** - * Sets the name of the sensor with a module and channel number. - * - * @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 (usually PWM) - */ - protected final void setName(String moduleType, int moduleNumber, int channel) { - m_sendableImpl.setName(moduleType, moduleNumber, channel); - } - - @Override - public final synchronized String getSubsystem() { - return m_sendableImpl.getSubsystem(); - } - - @Override - public final synchronized void setSubsystem(String subsystem) { - m_sendableImpl.setSubsystem(subsystem); - } - - /** - * Add a child component. - * - * @param child child component - */ - protected final void addChild(Object child) { - m_sendableImpl.addChild(child); - } - @Override public void stopMotor() { setDisabled(); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSparkMax.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSparkMax.java index 320d8a417a..29b28f2e62 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSparkMax.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSparkMax.java @@ -9,6 +9,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * REV Robotics SparkMax Speed Controller. @@ -36,6 +37,6 @@ public class PWMSparkMax extends PWMSpeedController { setZeroLatch(); HAL.report(tResourceType.kResourceType_RevSparkMaxPWM, getChannel()); - setName("PWMSparkMax", getChannel()); + SendableRegistry.setName(this, "PWMSparkMax", getChannel()); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMTalonSRX.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMTalonSRX.java index 2b42ed478b..691210ed39 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMTalonSRX.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMTalonSRX.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Cross the Road Electronics (CTRE) Talon SRX Speed Controller with PWM control. @@ -40,6 +41,6 @@ public class PWMTalonSRX extends PWMSpeedController { setZeroLatch(); HAL.report(tResourceType.kResourceType_PWMTalonSRX, getChannel()); - setName("PWMTalonSRX", getChannel()); + SendableRegistry.setName(this, "PWMTalonSRX", getChannel()); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMVictorSPX.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMVictorSPX.java index f1acb4332f..06076302dd 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMVictorSPX.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMVictorSPX.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Cross the Road Electronics (CTRE) Victor SPX Speed Controller with PWM control. @@ -40,6 +41,6 @@ public class PWMVictorSPX extends PWMSpeedController { setZeroLatch(); HAL.report(tResourceType.kResourceType_PWMVictorSPX, getChannel()); - setName("PWMVictorSPX", getChannel()); + SendableRegistry.setName(this, "PWMVictorSPX", getChannel()); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java index dd175eb2df..53ce284edc 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,12 +11,13 @@ import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.PDPJNI; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Class for getting voltage, current, temperature, power and energy from the Power Distribution * Panel over CAN. */ -public class PowerDistributionPanel extends SendableBase { +public class PowerDistributionPanel implements Sendable { private final int m_handle; /** @@ -29,7 +30,7 @@ public class PowerDistributionPanel extends SendableBase { m_handle = PDPJNI.initializePDP(module); HAL.report(tResourceType.kResourceType_PDP, module); - setName("PowerDistributionPanel", module); + SendableRegistry.addLW(this, "PowerDistributionPanel", module); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java index 94a980a42f..8539d8f355 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java @@ -15,6 +15,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.RelayJNI; import edu.wpi.first.hal.util.UncleanStatusException; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; @@ -93,8 +94,6 @@ public class Relay extends MotorSafety implements Sendable, AutoCloseable { private Direction m_direction; - private final SendableImpl m_sendableImpl; - /** * Common relay initialization method. This code is common to all Relay constructors and * initializes the relay and reserves all resources that need to be locked. Initially the relay is @@ -115,7 +114,7 @@ public class Relay extends MotorSafety implements Sendable, AutoCloseable { setSafetyEnabled(false); - setName("Relay", m_channel); + SendableRegistry.addLW(this, "Relay", m_channel); } /** @@ -125,8 +124,6 @@ public class Relay extends MotorSafety implements Sendable, AutoCloseable { * @param direction The direction that the Relay object will control. */ public Relay(final int channel, Direction direction) { - m_sendableImpl = new SendableImpl(true); - m_channel = channel; m_direction = requireNonNullParam(direction, "direction", "Relay"); initRelay(); @@ -144,7 +141,6 @@ public class Relay extends MotorSafety implements Sendable, AutoCloseable { @Override public void close() { - m_sendableImpl.close(); freeRelay(); } @@ -167,56 +163,6 @@ public class Relay extends MotorSafety implements Sendable, AutoCloseable { m_reverseHandle = 0; } - @Override - public final synchronized String getName() { - return m_sendableImpl.getName(); - } - - @Override - public final synchronized void setName(String name) { - m_sendableImpl.setName(name); - } - - /** - * Sets the name of the sensor with a channel number. - * - * @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 - */ - protected final void setName(String moduleType, int channel) { - m_sendableImpl.setName(moduleType, channel); - } - - /** - * Sets the name of the sensor with a module and channel number. - * - * @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 (usually PWM) - */ - protected final void setName(String moduleType, int moduleNumber, int channel) { - m_sendableImpl.setName(moduleType, moduleNumber, channel); - } - - @Override - public final synchronized String getSubsystem() { - return m_sendableImpl.getSubsystem(); - } - - @Override - public final synchronized void setSubsystem(String subsystem) { - m_sendableImpl.setSubsystem(subsystem); - } - - /** - * Add a child component. - * - * @param child child component - */ - protected final void addChild(Object child) { - m_sendableImpl.addChild(child); - } - /** * Set the relay state. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SD540.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SD540.java index 8f9ce0d9b8..cf81df65b3 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SD540.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SD540.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Mindsensors SD540 Speed Controller. @@ -34,7 +35,7 @@ public class SD540 extends PWMSpeedController { setZeroLatch(); HAL.report(tResourceType.kResourceType_MindsensorsSD540, getChannel()); - setName("SD540", getChannel()); + SendableRegistry.setName(this, "SD540", getChannel()); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Sendable.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Sendable.java index 76eb03cbdb..138f7f4a98 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Sendable.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Sendable.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -8,6 +8,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** @@ -18,40 +19,93 @@ public interface Sendable { * Gets the name of this {@link Sendable} object. * * @return Name + * @deprecated Use SendableRegistry.getName() */ - String getName(); + @Deprecated(since = "2020", forRemoval = true) + default String getName() { + return SendableRegistry.getName(this); + } /** * Sets the name of this {@link Sendable} object. * * @param name name + * @deprecated Use SendableRegistry.setName() */ - void setName(String name); + @Deprecated(since = "2020", forRemoval = true) + default void setName(String name) { + SendableRegistry.setName(this, name); + } /** * Sets both the subsystem name and device name of this {@link Sendable} object. * * @param subsystem subsystem name * @param name device name + * @deprecated Use SendableRegistry.setName() */ + @Deprecated(since = "2020", forRemoval = true) default void setName(String subsystem, String name) { - setSubsystem(subsystem); - setName(name); + SendableRegistry.setName(this, subsystem, name); + } + + /** + * Sets the name of the sensor with a channel number. + * + * @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 + * @deprecated Use SendableRegistry.setName() + */ + @Deprecated(since = "2020", forRemoval = true) + default void setName(String moduleType, int channel) { + SendableRegistry.setName(this, moduleType, channel); + } + + /** + * Sets the name of the sensor with a module and channel number. + * + * @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 (usually PWM) + * @deprecated Use SendableRegistry.setName() + */ + @Deprecated(since = "2020", forRemoval = true) + default void setName(String moduleType, int moduleNumber, int channel) { + SendableRegistry.setName(this, moduleType, moduleNumber, channel); } /** * Gets the subsystem name of this {@link Sendable} object. * * @return Subsystem name + * @deprecated Use SendableRegistry.getSubsystem() */ - String getSubsystem(); + @Deprecated(since = "2020", forRemoval = true) + default String getSubsystem() { + return SendableRegistry.getSubsystem(this); + } /** * Sets the subsystem name of this {@link Sendable} object. * * @param subsystem subsystem name + * @deprecated Use SendableRegistry.setSubsystem() */ - void setSubsystem(String subsystem); + @Deprecated(since = "2020", forRemoval = true) + default void setSubsystem(String subsystem) { + SendableRegistry.setSubsystem(this, subsystem); + } + + /** + * Add a child component. + * + * @param child child component + * @deprecated Use SendableRegistry.addChild() + */ + @Deprecated(since = "2020", forRemoval = true) + default void addChild(Object child) { + SendableRegistry.addChild(this, child); + } /** * Initializes this {@link Sendable} object. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableBase.java index b302a931bb..27b8fa2069 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableBase.java @@ -7,16 +7,15 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.wpilibj.livewindow.LiveWindow; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Base class for all sensors. Stores most recent status information as well as containing utility * functions for checking channels and error processing. + * @deprecated Use Sendable and SendableRegistry */ +@Deprecated(since = "2020", forRemoval = true) public abstract class SendableBase implements Sendable, AutoCloseable { - private String m_name = ""; - private String m_subsystem = "Ungrouped"; - /** * Creates an instance of the sensor base. */ @@ -31,67 +30,12 @@ public abstract class SendableBase implements Sendable, AutoCloseable { */ public SendableBase(boolean addLiveWindow) { if (addLiveWindow) { - LiveWindow.add(this); + SendableRegistry.addLW(this, ""); + } else { + SendableRegistry.add(this, ""); } } - @Deprecated - public void free() { - close(); - } - @Override - public void close() { - LiveWindow.remove(this); - } - - @Override - public final String getName() { - return m_name; - } - - @Override - public final void setName(String name) { - m_name = name; - } - - /** - * Sets the name of the sensor with a channel number. - * - * @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 - */ - protected final void setName(String moduleType, int channel) { - setName(moduleType + "[" + channel + "]"); - } - - /** - * Sets the name of the sensor with a module and channel number. - * - * @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 (usually PWM) - */ - protected final void setName(String moduleType, int moduleNumber, int channel) { - setName(moduleType + "[" + moduleNumber + "," + channel + "]"); - } - - @Override - public final String getSubsystem() { - return m_subsystem; - } - - @Override - public final void setSubsystem(String subsystem) { - m_subsystem = subsystem; - } - - /** - * Add a child component. - * - * @param child child component - */ - protected final void addChild(Object child) { - LiveWindow.addChild(this, child); - } + public void close() {} } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableImpl.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableImpl.java deleted file mode 100644 index 0fa2e746f9..0000000000 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableImpl.java +++ /dev/null @@ -1,101 +0,0 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2018 FIRST. All Rights Reserved. */ -/* Open Source Software - may be modified and shared by FRC teams. The code */ -/* must be accompanied by the FIRST BSD license file in the root directory of */ -/* the project. */ -/*----------------------------------------------------------------------------*/ - -package edu.wpi.first.wpilibj; - -import edu.wpi.first.wpilibj.livewindow.LiveWindow; -import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; - -/** - * The base interface for objects that can be sent over the network through network tables. - */ -public class SendableImpl implements Sendable, AutoCloseable { - private String m_name = ""; - private String m_subsystem = "Ungrouped"; - - /** - * Creates an instance of the sensor base. - */ - public SendableImpl() { - this(true); - } - - /** - * Creates an instance of the sensor base. - * - * @param addLiveWindow if true, add this Sendable to LiveWindow - */ - public SendableImpl(boolean addLiveWindow) { - if (addLiveWindow) { - LiveWindow.add(this); - } - } - - @Deprecated - public void free() { - close(); - } - - @Override - public void close() { - LiveWindow.remove(this); - } - - @Override - public synchronized String getName() { - return m_name; - } - - @Override - public synchronized void setName(String name) { - m_name = name; - } - - /** - * Sets the name of the sensor with a channel number. - * - * @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 void setName(String moduleType, int channel) { - setName(moduleType + "[" + channel + "]"); - } - - /** - * Sets the name of the sensor with a module and channel number. - * - * @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 (usually PWM) - */ - public void setName(String moduleType, int moduleNumber, int channel) { - setName(moduleType + "[" + moduleNumber + "," + channel + "]"); - } - - @Override - public synchronized String getSubsystem() { - return m_subsystem; - } - - @Override - public synchronized void setSubsystem(String subsystem) { - m_subsystem = subsystem; - } - - @Override - public void initSendable(SendableBuilder builder) { - } - - /** - * Add a child component. - * - * @param child child component - */ - public void addChild(Object child) { - LiveWindow.addChild(this, child); - } -} diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java index 1abe6bb7f5..dee705130a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,6 +10,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Standard hobby style servo. @@ -39,7 +40,7 @@ public class Servo extends PWM { setPeriodMultiplier(PeriodMultiplier.k4X); HAL.report(tResourceType.kResourceType_Servo, getChannel()); - setName("Servo", getChannel()); + SendableRegistry.setName(this, "Servo", getChannel()); } 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 014ec1028d..47b7fa098b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,6 +11,7 @@ import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.SolenoidJNI; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Solenoid class for running high voltage Digital Output on the PCM. @@ -18,7 +19,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; *

The Solenoid class is typically used for pneumatic solenoids, but could be used for any * device within the current spec of the PCM. */ -public class Solenoid extends SolenoidBase { +public class Solenoid extends SolenoidBase implements Sendable, AutoCloseable { private final int m_channel; // The channel to control. private int m_solenoidHandle; @@ -48,12 +49,11 @@ public class Solenoid extends SolenoidBase { m_solenoidHandle = SolenoidJNI.initializeSolenoidPort(portHandle); HAL.report(tResourceType.kResourceType_Solenoid, m_channel, m_moduleNumber); - setName("Solenoid", m_moduleNumber, m_channel); + SendableRegistry.addLW(this, "Solenoid", m_moduleNumber, m_channel); } @Override public void close() { - super.close(); SolenoidJNI.freeSolenoidPort(m_solenoidHandle); m_solenoidHandle = 0; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SolenoidBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SolenoidBase.java index 59c6c3d81f..a778d8c210 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SolenoidBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SolenoidBase.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -13,7 +13,7 @@ import edu.wpi.first.hal.SolenoidJNI; * SolenoidBase class is the common base class for the {@link Solenoid} and {@link DoubleSolenoid} * classes. */ -public abstract class SolenoidBase extends SendableBase { +public class SolenoidBase { protected final int m_moduleNumber; // The number of the solenoid module being used. /** @@ -21,7 +21,7 @@ public abstract class SolenoidBase extends SendableBase { * * @param moduleNumber The PCM CAN ID */ - public SolenoidBase(final int moduleNumber) { + protected SolenoidBase(final int moduleNumber) { m_moduleNumber = moduleNumber; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Spark.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Spark.java index aa7953ab9d..ea2a8a7204 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Spark.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Spark.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * REV Robotics SPARK Speed Controller. @@ -34,7 +35,7 @@ public class Spark extends PWMSpeedController { setZeroLatch(); HAL.report(tResourceType.kResourceType_RevSPARK, getChannel()); - setName("Spark", getChannel()); + SendableRegistry.setName(this, "Spark", getChannel()); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java index 9158bb3fff..bfe57fcd0b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -8,11 +8,12 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Allows multiple {@link SpeedController} objects to be linked together. */ -public class SpeedControllerGroup extends SendableBase implements SpeedController { +public class SpeedControllerGroup implements SpeedController, Sendable { private boolean m_isInverted; private final SpeedController[] m_speedControllers; private static int instances; @@ -27,13 +28,13 @@ public class SpeedControllerGroup extends SendableBase implements SpeedControlle SpeedController... speedControllers) { m_speedControllers = new SpeedController[speedControllers.length + 1]; m_speedControllers[0] = speedController; - addChild(speedController); + SendableRegistry.addChild(this, speedController); for (int i = 0; i < speedControllers.length; i++) { m_speedControllers[i + 1] = speedControllers[i]; - addChild(speedControllers[i]); + SendableRegistry.addChild(this, speedControllers[i]); } instances++; - setName("SpeedControllerGroup", instances); + SendableRegistry.addLW(this, "tSpeedControllerGroup", instances); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Talon.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Talon.java index 334d9e3257..861fca6587 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Talon.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Talon.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * Cross the Road Electronics (CTRE) Talon and Talon SR Speed Controller. @@ -39,6 +40,6 @@ public class Talon extends PWMSpeedController { setZeroLatch(); HAL.report(tResourceType.kResourceType_Talon, getChannel()); - setName("Talon", getChannel()); + SendableRegistry.setName(this, "Talon", getChannel()); } } 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 afa3017a21..81f0e50643 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java @@ -13,6 +13,7 @@ import java.util.List; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import static java.util.Objects.requireNonNull; @@ -25,7 +26,7 @@ import static java.util.Objects.requireNonNull; * echo is received. The time that the line is high determines the round trip distance (time of * flight). */ -public class Ultrasonic extends SendableBase implements PIDSource { +public class Ultrasonic implements PIDSource, Sendable, AutoCloseable { /** * The units to return when PIDGet is called. */ @@ -101,7 +102,7 @@ public class Ultrasonic extends SendableBase implements PIDSource { m_sensors.add(this); m_counter = new Counter(m_echoChannel); // set up counter for this - addChild(m_counter); + SendableRegistry.addChild(this, m_counter); // sensor m_counter.setMaxPeriod(1.0); m_counter.setSemiPeriodMode(true); @@ -111,7 +112,7 @@ public class Ultrasonic extends SendableBase implements PIDSource { m_instances++; HAL.report(tResourceType.kResourceType_Ultrasonic, m_instances); - setName("Ultrasonic", m_echoChannel.getChannel()); + SendableRegistry.addLW(this, "Ultrasonic", m_echoChannel.getChannel()); } /** @@ -128,8 +129,8 @@ public class Ultrasonic extends SendableBase implements PIDSource { public Ultrasonic(final int pingChannel, final int echoChannel, Unit units) { m_pingChannel = new DigitalOutput(pingChannel); m_echoChannel = new DigitalInput(echoChannel); - addChild(m_pingChannel); - addChild(m_echoChannel); + SendableRegistry.addChild(this, m_pingChannel); + SendableRegistry.addChild(this, m_echoChannel); m_allocatedChannels = true; m_units = units; initialize(); @@ -191,7 +192,6 @@ public class Ultrasonic extends SendableBase implements PIDSource { */ @Override public synchronized void close() { - super.close(); final boolean wasAutomaticMode = m_automaticEnabled; setAutomaticMode(false); if (m_allocatedChannels) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Victor.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Victor.java index b1aeeab178..fa9dc1731f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Victor.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Victor.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * VEX Robotics Victor 888 Speed Controller The Vex Robotics Victor 884 Speed Controller can also @@ -41,6 +42,6 @@ public class Victor extends PWMSpeedController { setZeroLatch(); HAL.report(tResourceType.kResourceType_Victor, getChannel()); - setName("Victor", getChannel()); + SendableRegistry.setName(this, "Victor", getChannel()); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/VictorSP.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/VictorSP.java index 3de2a0a36b..019153e523 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/VictorSP.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/VictorSP.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -9,6 +9,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * VEX Robotics Victor SP Speed Controller. @@ -39,6 +40,6 @@ public class VictorSP extends PWMSpeedController { setZeroLatch(); HAL.report(tResourceType.kResourceType_VictorSP, getChannel()); - setName("VictorSP", getChannel()); + SendableRegistry.setName(this, "VictorSP", getChannel()); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java index c20e62ee15..f0517768c2 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -7,7 +7,7 @@ package edu.wpi.first.wpilibj.buttons; -import edu.wpi.first.wpilibj.SendableBase; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.command.Command; import edu.wpi.first.wpilibj.command.Scheduler; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; @@ -23,7 +23,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; * certain sensor input). For this, they only have to write the {@link Trigger#get()} method to get * the full functionality of the Trigger class. */ -public abstract class Trigger extends SendableBase { +public abstract class Trigger implements Sendable { private volatile boolean m_sendablePressed; /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Command.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Command.java index 0033f58353..1b50dd6286 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Command.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Command.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,9 +10,10 @@ package edu.wpi.first.wpilibj.command; import java.util.Enumeration; import edu.wpi.first.wpilibj.RobotState; -import edu.wpi.first.wpilibj.SendableBase; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * The Command class is at the very core of the entire command framework. Every command can be @@ -40,7 +41,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; * @see IllegalUseOfCommandException */ @SuppressWarnings("PMD.TooManyMethods") -public abstract class Command extends SendableBase { +public abstract class Command implements Sendable { /** * The time since this command was initialized. */ @@ -100,9 +101,8 @@ public abstract class Command extends SendableBase { * Creates a new command. The name of this command will be set to its class name. */ public Command() { - super(false); String name = getClass().getName(); - setName(name.substring(name.lastIndexOf('.') + 1)); + SendableRegistry.add(this, name.substring(name.lastIndexOf('.') + 1)); } /** @@ -112,11 +112,10 @@ public abstract class Command extends SendableBase { * @throws IllegalArgumentException if name is null */ public Command(String name) { - super(false); if (name == null) { throw new IllegalArgumentException("Name must not be null."); } - setName(name); + SendableRegistry.add(this, name); } /** @@ -596,6 +595,46 @@ public abstract class Command extends SendableBase { return m_runWhenDisabled; } + /** + * Gets the name of this Command. + * + * @return Name + */ + @Override + public String getName() { + return SendableRegistry.getName(this); + } + + /** + * Sets the name of this Command. + * + * @param name name + */ + @Override + public void setName(String name) { + SendableRegistry.setName(this, name); + } + + /** + * Gets the subsystem name of this Command. + * + * @return Subsystem name + */ + @Override + public String getSubsystem() { + return SendableRegistry.getSubsystem(this); + } + + /** + * Sets the subsystem name of this Command. + * + * @param subsystem subsystem name + */ + @Override + public void setSubsystem(String subsystem) { + SendableRegistry.setSubsystem(this, subsystem); + } + /** * The string representation for a {@link Command} is by default its name. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java index 8302e22330..1c4f4706a4 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -15,9 +15,10 @@ 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.NetworkTableEntry; -import edu.wpi.first.wpilibj.SendableBase; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * The {@link Scheduler} is a singleton which holds the top-level running commands. It is in charge @@ -31,7 +32,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; * * @see Command */ -public final class Scheduler extends SendableBase { +public final class Scheduler implements Sendable { /** * The Singleton Instance. */ @@ -95,7 +96,7 @@ public final class Scheduler extends SendableBase { */ private Scheduler() { HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand_Scheduler); - setName("Scheduler"); + SendableRegistry.addLW(this, "Scheduler"); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java index 0da80c253c..41f4ed131f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -10,9 +10,8 @@ package edu.wpi.first.wpilibj.command; import java.util.Collections; import edu.wpi.first.wpilibj.Sendable; -import edu.wpi.first.wpilibj.SendableBase; -import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * This class defines a major component of the robot. @@ -28,7 +27,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; * * @see Command */ -public abstract class Subsystem extends SendableBase { +public abstract class Subsystem implements Sendable { /** * Whether or not getDefaultCommand() was called. */ @@ -50,7 +49,7 @@ public abstract class Subsystem extends SendableBase { * @param name the name of the subsystem */ public Subsystem(String name) { - setName(name, name); + SendableRegistry.addLW(this, name, name); Scheduler.getInstance().registerSubsystem(this); } @@ -60,7 +59,7 @@ public abstract class Subsystem extends SendableBase { public Subsystem() { String name = getClass().getName(); name = name.substring(name.lastIndexOf('.') + 1); - setName(name, name); + SendableRegistry.addLW(this, name, name); Scheduler.getInstance().registerSubsystem(this); m_currentCommandChanged = true; } @@ -179,8 +178,8 @@ public abstract class Subsystem extends SendableBase { * @param child sendable */ public void addChild(String name, Sendable child) { - child.setName(getSubsystem(), name); - LiveWindow.add(child); + SendableRegistry.addLW(child, getSubsystem(), name); + SendableRegistry.addChild(this, child); } /** @@ -189,8 +188,49 @@ public abstract class Subsystem extends SendableBase { * @param child sendable */ public void addChild(Sendable child) { - child.setSubsystem(getSubsystem()); - LiveWindow.add(child); + SendableRegistry.setSubsystem(child, getSubsystem()); + SendableRegistry.enableLiveWindow(child); + SendableRegistry.addChild(this, child); + } + + /** + * Gets the name of this Subsystem. + * + * @return Name + */ + @Override + public String getName() { + return SendableRegistry.getName(this); + } + + /** + * Sets the name of this Subsystem. + * + * @param name name + */ + @Override + public void setName(String name) { + SendableRegistry.setName(this, name); + } + + /** + * Gets the subsystem name of this Subsystem. + * + * @return Subsystem name + */ + @Override + public String getSubsystem() { + return SendableRegistry.getSubsystem(this); + } + + /** + * Sets the subsystem name of this Subsystem. + * + * @param subsystem subsystem name + */ + @Override + public void setSubsystem(String subsystem) { + SendableRegistry.setSubsystem(this, subsystem); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/controller/PIDController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/controller/PIDController.java index d5c677d54f..8a3c290b05 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/controller/PIDController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/controller/PIDController.java @@ -9,15 +9,16 @@ package edu.wpi.first.wpilibj.controller; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; -import edu.wpi.first.wpilibj.SendableBase; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import edu.wpi.first.wpiutil.math.MathUtils; /** * Implements a PID control loop. */ @SuppressWarnings("PMD.TooManyFields") -public class PIDController extends SendableBase { +public class PIDController implements Sendable { private static int instances; // Factor for "proportional" control @@ -97,7 +98,7 @@ public class PIDController extends SendableBase { m_period = period; instances++; - setName("PIDController", instances); + SendableRegistry.addLW(this, "PIDController", instances); HAL.report(tResourceType.kResourceType_PIDController, instances); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/controller/ProfiledPIDController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/controller/ProfiledPIDController.java index 60e06fa64b..ebc786f204 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/controller/ProfiledPIDController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/controller/ProfiledPIDController.java @@ -7,7 +7,7 @@ package edu.wpi.first.wpilibj.controller; -import edu.wpi.first.wpilibj.SendableBase; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile; @@ -16,7 +16,7 @@ import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile; * profile. */ @SuppressWarnings("PMD.TooManyMethods") -public class ProfiledPIDController extends SendableBase { +public class ProfiledPIDController implements Sendable { private PIDController m_controller; private TrapezoidProfile.State m_goal = new TrapezoidProfile.State(); private TrapezoidProfile.State m_setpoint = new TrapezoidProfile.State(); 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 2c148fc40e..80400f3168 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 @@ -12,9 +12,11 @@ import java.util.StringJoiner; import edu.wpi.first.hal.FRCNetComm.tInstances; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.SpeedController; import edu.wpi.first.wpilibj.SpeedControllerGroup; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import edu.wpi.first.wpiutil.math.MathUtils; /** @@ -94,7 +96,7 @@ import edu.wpi.first.wpiutil.math.MathUtils; * {@link edu.wpi.first.wpilibj.RobotDrive#drive(double, double)} with the addition of a quick turn * mode. However, it is not designed to give exactly the same response. */ -public class DifferentialDrive extends RobotDriveBase { +public class DifferentialDrive extends RobotDriveBase implements Sendable { public static final double kDefaultQuickStopThreshold = 0.2; public static final double kDefaultQuickStopAlpha = 0.1; @@ -119,10 +121,10 @@ public class DifferentialDrive extends RobotDriveBase { verify(leftMotor, rightMotor); m_leftMotor = leftMotor; m_rightMotor = rightMotor; - addChild(m_leftMotor); - addChild(m_rightMotor); + SendableRegistry.addChild(this, m_leftMotor); + SendableRegistry.addChild(this, m_rightMotor); instances++; - setName("DifferentialDrive", instances); + SendableRegistry.addLW(this, "DifferentialDrive", instances); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java index 07d3ba5268..95c7c18289 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java @@ -12,8 +12,10 @@ import java.util.StringJoiner; import edu.wpi.first.hal.FRCNetComm.tInstances; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.SpeedController; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import edu.wpi.first.wpiutil.math.MathUtils; /** @@ -40,7 +42,7 @@ import edu.wpi.first.wpiutil.math.MathUtils; * points down. Rotations follow the right-hand rule, so clockwise rotation around the Z axis is * positive. */ -public class KilloughDrive extends RobotDriveBase { +public class KilloughDrive extends RobotDriveBase implements Sendable { public static final double kDefaultLeftMotorAngle = 60.0; public static final double kDefaultRightMotorAngle = 120.0; public static final double kDefaultBackMotorAngle = 270.0; @@ -100,11 +102,11 @@ public class KilloughDrive extends RobotDriveBase { Math.sin(rightMotorAngle * (Math.PI / 180.0))); m_backVec = new Vector2d(Math.cos(backMotorAngle * (Math.PI / 180.0)), Math.sin(backMotorAngle * (Math.PI / 180.0))); - addChild(m_leftMotor); - addChild(m_rightMotor); - addChild(m_backMotor); + SendableRegistry.addChild(this, m_leftMotor); + SendableRegistry.addChild(this, m_rightMotor); + SendableRegistry.addChild(this, m_backMotor); instances++; - setName("KilloughDrive", instances); + SendableRegistry.addLW(this, "KilloughDrive", instances); } /** 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 c6a67d51bc..4ede5a48c2 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 @@ -12,8 +12,10 @@ import java.util.StringJoiner; import edu.wpi.first.hal.FRCNetComm.tInstances; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.SpeedController; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; import edu.wpi.first.wpiutil.math.MathUtils; /** @@ -59,7 +61,7 @@ import edu.wpi.first.wpiutil.math.MathUtils; * {@link edu.wpi.first.wpilibj.RobotDrive#mecanumDrive_Polar(double, double, double)} if a * deadband of 0 is used. */ -public class MecanumDrive extends RobotDriveBase { +public class MecanumDrive extends RobotDriveBase implements Sendable { private static int instances; private final SpeedController m_frontLeftMotor; @@ -82,12 +84,12 @@ public class MecanumDrive extends RobotDriveBase { m_rearLeftMotor = rearLeftMotor; m_frontRightMotor = frontRightMotor; m_rearRightMotor = rearRightMotor; - addChild(m_frontLeftMotor); - addChild(m_rearLeftMotor); - addChild(m_frontRightMotor); - addChild(m_rearRightMotor); + SendableRegistry.addChild(this, m_frontLeftMotor); + SendableRegistry.addChild(this, m_rearLeftMotor); + SendableRegistry.addChild(this, m_frontRightMotor); + SendableRegistry.addChild(this, m_rearRightMotor); instances++; - setName("MecanumDrive", instances); + SendableRegistry.addLW(this, "MecanumDrive", instances); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java index f82d6ade89..785a0c5ebd 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java @@ -8,21 +8,17 @@ package edu.wpi.first.wpilibj.drive; import edu.wpi.first.wpilibj.MotorSafety; -import edu.wpi.first.wpilibj.Sendable; -import edu.wpi.first.wpilibj.SendableImpl; /** * Common base class for drive platforms. */ -public abstract class RobotDriveBase extends MotorSafety implements Sendable, AutoCloseable { +public abstract class RobotDriveBase extends MotorSafety { public static final double kDefaultDeadband = 0.02; public static final double kDefaultMaxOutput = 1.0; protected double m_deadband = kDefaultDeadband; protected double m_maxOutput = kDefaultMaxOutput; - private final SendableImpl m_sendableImpl; - /** * The location of a motor on the robot for the purpose of driving. */ @@ -42,65 +38,7 @@ public abstract class RobotDriveBase extends MotorSafety implements Sendable, Au * RobotDriveBase constructor. */ public RobotDriveBase() { - m_sendableImpl = new SendableImpl(true); - setSafetyEnabled(true); - setName("RobotDriveBase"); - } - - @Override - public void close() { - m_sendableImpl.close(); - } - - @Override - public final synchronized String getName() { - return m_sendableImpl.getName(); - } - - @Override - public final synchronized void setName(String name) { - m_sendableImpl.setName(name); - } - - /** - * Sets the name of the sensor with a channel number. - * - * @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 - */ - protected final void setName(String moduleType, int channel) { - m_sendableImpl.setName(moduleType, channel); - } - - /** - * Sets the name of the sensor with a module and channel number. - * - * @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 (usually PWM) - */ - protected final void setName(String moduleType, int moduleNumber, int channel) { - m_sendableImpl.setName(moduleType, moduleNumber, channel); - } - - @Override - public final synchronized String getSubsystem() { - return m_sendableImpl.getSubsystem(); - } - - @Override - public final synchronized void setSubsystem(String subsystem) { - m_sendableImpl.setSubsystem(subsystem); - } - - /** - * Add a child component. - * - * @param child child component - */ - protected final void addChild(Object child) { - m_sendableImpl.addChild(child); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java index 4a5b2de47d..a21e6d57ce 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -56,10 +56,4 @@ public interface Gyro extends AutoCloseable { * @return the current rate in degrees per second */ double getRate(); - - /** - * Free the resources used by the gyro. - */ - @Deprecated - void free(); } 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 index 92a2678006..b5972a9080 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java @@ -7,38 +7,27 @@ package edu.wpi.first.wpilibj.livewindow; -import java.util.HashMap; -import java.util.Map; - import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.command.Scheduler; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * The LiveWindow class is the public interface for putting sensors and actuators on the * LiveWindow. */ -@SuppressWarnings("PMD.TooManyMethods") public class LiveWindow { private static class Component { - Component(Sendable sendable, Sendable parent) { - m_sendable = sendable; - m_parent = parent; - } - - final Sendable m_sendable; - Sendable m_parent; final SendableBuilderImpl m_builder = new SendableBuilderImpl(); boolean m_firstTime = true; boolean m_telemetryEnabled = true; } - @SuppressWarnings("PMD.UseConcurrentHashMap") - private static final Map components = new HashMap<>(); + private static final int dataHandle = SendableRegistry.getDataHandle(); private static final NetworkTable liveWindowTable = NetworkTableInstance.getDefault().getTable("LiveWindow"); private static final NetworkTable statusTable = liveWindowTable.getSubTable(".status"); @@ -47,6 +36,15 @@ public class LiveWindow { private static boolean liveWindowEnabled; private static boolean telemetryEnabled = true; + 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!"); } @@ -75,53 +73,19 @@ public class LiveWindow { scheduler.removeAll(); } else { System.out.println("stopping live window mode."); - for (Component component : components.values()) { - component.m_builder.stopLiveWindowMode(); - } + SendableRegistry.foreachLiveWindow(dataHandle, + (sendable, name, subsystem, parent, data) -> { + if (data != null) { + ((Component) data).m_builder.stopLiveWindowMode(); + } + return data; + }); scheduler.enable(); } enabledEntry.setBoolean(enabled); } } - /** - * Add a component to the LiveWindow. - * - * @param sendable component to add - */ - public static synchronized void add(Sendable sendable) { - components.putIfAbsent(sendable, new Component(sendable, null)); - } - - /** - * Add a child component to a component. - * - * @param parent parent component - * @param child child component - */ - public static synchronized void addChild(Sendable parent, Object child) { - Component component = components.get(child); - if (component == null) { - component = new Component(null, parent); - components.put(child, component); - } else { - component.m_parent = parent; - } - component.m_telemetryEnabled = false; - } - - /** - * Remove a component from the LiveWindow. - * - * @param sendable component to remove - */ - public static synchronized void remove(Sendable sendable) { - Component component = components.remove(sendable); - if (component != null && isEnabled()) { - component.m_builder.stopLiveWindowMode(); - } - } - /** * Enable telemetry for a single component. * @@ -130,10 +94,7 @@ public class LiveWindow { public static synchronized void enableTelemetry(Sendable sendable) { // Re-enable global setting in case disableAllTelemetry() was called. telemetryEnabled = true; - Component component = components.get(sendable); - if (component != null) { - component.m_telemetryEnabled = true; - } + getOrAdd(sendable).m_telemetryEnabled = true; } /** @@ -142,10 +103,7 @@ public class LiveWindow { * @param sendable component */ public static synchronized void disableTelemetry(Sendable sendable) { - Component component = components.get(sendable); - if (component != null) { - component.m_telemetryEnabled = false; - } + getOrAdd(sendable).m_telemetryEnabled = false; } /** @@ -153,9 +111,13 @@ public class LiveWindow { */ public static synchronized void disableAllTelemetry() { telemetryEnabled = false; - for (Component component : components.values()) { - component.m_telemetryEnabled = false; - } + SendableRegistry.foreachLiveWindow(dataHandle, (sendable, name, subsystem, parent, data) -> { + if (data == null) { + data = new Component(); + } + ((Component) data).m_telemetryEnabled = false; + return data; + }); } /** @@ -164,48 +126,58 @@ public class LiveWindow { *

Actuators are handled through callbacks on their value changing from the * SmartDashboard widgets. */ - @SuppressWarnings("PMD.CyclomaticComplexity") + @SuppressWarnings({"PMD.CyclomaticComplexity", "PMD.NPathComplexity"}) public static synchronized void updateValues() { // Only do this if either LiveWindow mode or telemetry is enabled. if (!liveWindowEnabled && !telemetryEnabled) { return; } - for (Component component : components.values()) { - if (component.m_sendable != null && component.m_parent == null - && (liveWindowEnabled || component.m_telemetryEnabled)) { - 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. - String name = component.m_sendable.getName(); - if (name.isEmpty()) { - continue; - } - String subsystem = component.m_sendable.getSubsystem(); - NetworkTable ssTable = liveWindowTable.getSubTable(subsystem); - NetworkTable table; - // Treat name==subsystem as top level of subsystem - if (name.equals(subsystem)) { - table = ssTable; - } else { - table = ssTable.getSubTable(name); - } - table.getEntry(".name").setString(name); - component.m_builder.setTable(table); - component.m_sendable.initSendable(component.m_builder); - ssTable.getEntry(".type").setString("LW Subsystem"); - - component.m_firstTime = false; - } - - if (startLiveWindow) { - component.m_builder.startLiveWindowMode(); - } - component.m_builder.updateTable(); + SendableRegistry.foreachLiveWindow(dataHandle, (sendable, name, subsystem, parent, data) -> { + if (sendable == null || parent != null) { + return data; } - } + + if (data == null) { + data = new Component(); + } + + Component component = (Component) data; + + if (!liveWindowEnabled && !component.m_telemetryEnabled) { + return data; + } + + 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 (name.isEmpty()) { + return data; + } + NetworkTable ssTable = liveWindowTable.getSubTable(subsystem); + NetworkTable table; + // Treat name==subsystem as top level of subsystem + if (name.equals(subsystem)) { + table = ssTable; + } else { + table = ssTable.getSubTable(name); + } + table.getEntry(".name").setString(name); + component.m_builder.setTable(table); + sendable.initSendable(component.m_builder); + ssTable.getEntry(".type").setString("LW Subsystem"); + + component.m_firstTime = false; + } + + if (startLiveWindow) { + component.m_builder.startLiveWindowMode(); + } + component.m_builder.updateTable(); + return data; + }); startLiveWindow = false; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java index 0fb1e57c86..a18e4c8c27 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java @@ -22,6 +22,7 @@ import java.util.function.Supplier; import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.wpilibj.Sendable; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * A helper class for Shuffleboard containers to handle common child operations. @@ -66,10 +67,11 @@ final class ContainerHelper { } ComplexWidget add(Sendable sendable) throws IllegalArgumentException { - if (sendable.getName() == null || sendable.getName().isEmpty()) { + String name = SendableRegistry.getName(sendable); + if (name.isEmpty()) { throw new IllegalArgumentException("Sendable must have a name"); } - return add(sendable.getName(), sendable); + return add(name, sendable); } SimpleWidget add(String title, Object defaultValue) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java index 7aa93eefe3..208982246d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,13 +12,13 @@ import java.util.WeakHashMap; import edu.wpi.cscore.VideoSource; import edu.wpi.first.wpilibj.Sendable; -import edu.wpi.first.wpilibj.SendableBase; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * A wrapper to make video sources sendable and usable from Shuffleboard. */ -public final class SendableCameraWrapper extends SendableBase { +public final class SendableCameraWrapper implements Sendable { private static final String kProtocol = "camera_server://"; private static Map m_wrappers = new WeakHashMap<>(); @@ -32,9 +32,8 @@ public final class SendableCameraWrapper extends SendableBase { * @param source the source to wrap */ private SendableCameraWrapper(VideoSource source) { - super(false); String name = source.getName(); - setName(name); + SendableRegistry.add(this, name); m_uri = kProtocol + name; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java index d1b110ff03..8be9f87943 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java @@ -15,7 +15,7 @@ import java.util.concurrent.atomic.AtomicInteger; import java.util.concurrent.locks.ReentrantLock; import edu.wpi.first.networktables.NetworkTableEntry; -import edu.wpi.first.wpilibj.SendableBase; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.command.Command; import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; @@ -32,7 +32,7 @@ import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; * * @param The type of the values to be stored */ -public class SendableChooser extends SendableBase { +public class SendableChooser implements Sendable { /** * The key for the default value. */ @@ -65,8 +65,8 @@ public class SendableChooser extends SendableBase { * Instantiates a {@link SendableChooser}. */ public SendableChooser() { - super(false); m_instance = s_instances.getAndIncrement(); + SendableRegistry.add(this, "SendableChooser", m_instance); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableRegistry.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableRegistry.java new file mode 100644 index 0000000000..df5b5295f3 --- /dev/null +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableRegistry.java @@ -0,0 +1,437 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +package edu.wpi.first.wpilibj.smartdashboard; + +import java.lang.ref.WeakReference; +import java.util.Arrays; +import java.util.Map; +import java.util.WeakHashMap; + +import edu.wpi.first.wpilibj.Sendable; + + +/** + * The SendableRegistry class is the public interface for registering sensors + * and actuators for use on dashboards and LiveWindow. + */ +@SuppressWarnings("PMD.TooManyMethods") +public class SendableRegistry { + private static class Component { + Component() {} + + Component(Sendable sendable) { + m_sendable = new WeakReference<>(sendable); + } + + WeakReference m_sendable; + String m_name; + String m_subsystem = "Ungrouped"; + WeakReference m_parent; + boolean m_liveWindow; + Object[] m_data; + + void setName(String moduleType, int channel) { + m_name = moduleType + "[" + channel + "]"; + } + + void setName(String moduleType, int moduleNumber, int channel) { + m_name = moduleType + "[" + moduleNumber + "," + channel + "]"; + } + } + + private static final Map components = new WeakHashMap<>(); + private static int nextDataHandle; + + private static Component getOrAdd(Sendable sendable) { + Component comp = components.get(sendable); + if (comp == null) { + comp = new Component(sendable); + components.put(sendable, comp); + } else { + if (comp.m_sendable == null) { + comp.m_sendable = new WeakReference<>(sendable); + } + } + return comp; + } + + private SendableRegistry() { + throw new UnsupportedOperationException("This is a utility class!"); + } + + /** + * Adds an object to the registry. + * + * @param sendable object to add + * @param name component name + */ + public static synchronized void add(Sendable sendable, String name) { + Component comp = getOrAdd(sendable); + comp.m_name = name; + } + + /** + * Adds an object to the registry. + * + * @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 add(Sendable sendable, String moduleType, int channel) { + Component comp = getOrAdd(sendable); + comp.setName(moduleType, channel); + } + + /** + * Adds an object to the registry. + * + * @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 add(Sendable sendable, String moduleType, int moduleNumber, + int channel) { + Component comp = getOrAdd(sendable); + comp.setName(moduleType, moduleNumber, channel); + } + + /** + * Adds an object to the registry. + * + * @param sendable object to add + * @param subsystem subsystem name + * @param name component name + */ + public static synchronized void add(Sendable sendable, String subsystem, String name) { + Component comp = getOrAdd(sendable); + comp.m_name = name; + 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); + 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); + 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); + 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); + 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. + * + * @param parent parent object + * @param child child object + */ + public static synchronized void addChild(Sendable parent, Object child) { + Component comp = components.get(child); + if (comp == null) { + comp = new Component(); + components.put(child, comp); + } + comp.m_parent = new WeakReference<>(parent); + } + + /** + * Removes an object from the registry. + * + * @param sendable object to remove + * @return true if the object was removed; false if it was not present + */ + public static synchronized boolean remove(Sendable sendable) { + return components.remove(sendable) != null; + } + + /** + * Determines if an object is in the registry. + * + * @param sendable object to check + * @return True if in registry, false if not. + */ + public static synchronized boolean contains(Sendable sendable) { + return components.containsKey(sendable); + } + + /** + * Gets the name of an object. + * + * @param sendable object + * @return Name (empty if object is not in registry) + */ + public static synchronized String getName(Sendable sendable) { + Component comp = components.get(sendable); + if (comp == null) { + return ""; + } + return comp.m_name; + } + + /** + * Sets the name of an object. + * + * @param sendable object + * @param name name + */ + public static synchronized void setName(Sendable sendable, String name) { + Component comp = components.get(sendable); + if (comp != null) { + comp.m_name = name; + } + } + + /** + * Sets the name of an object with a channel number. + * + * @param sendable object + * @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 setName(Sendable sendable, String moduleType, int channel) { + Component comp = components.get(sendable); + if (comp != null) { + comp.setName(moduleType, channel); + } + } + + /** + * Sets the name of an object with a module and channel number. + * + * @param sendable object + * @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 setName(Sendable sendable, String moduleType, int moduleNumber, + int channel) { + Component comp = components.get(sendable); + if (comp != null) { + comp.setName(moduleType, moduleNumber, channel); + } + } + + /** + * Sets both the subsystem name and device name of an object. + * + * @param sendable object + * @param subsystem subsystem name + * @param name device name + */ + public static synchronized void setName(Sendable sendable, String subsystem, String name) { + Component comp = components.get(sendable); + if (comp != null) { + comp.m_name = name; + comp.m_subsystem = subsystem; + } + } + + /** + * Gets the subsystem name of an object. + * + * @param sendable object + * @return Subsystem name (empty if object is not in registry) + */ + public static synchronized String getSubsystem(Sendable sendable) { + Component comp = components.get(sendable); + if (comp == null) { + return ""; + } + return comp.m_subsystem; + } + + /** + * Sets the subsystem name of an object. + * + * @param sendable object + * @param subsystem subsystem name + */ + public static synchronized void setSubsystem(Sendable sendable, String subsystem) { + Component comp = components.get(sendable); + if (comp != null) { + comp.m_subsystem = subsystem; + } + } + + /** + * Gets a unique handle for setting/getting data with setData() and getData(). + * + * @return Handle + */ + public static synchronized int getDataHandle() { + return nextDataHandle++; + } + + /** + * Associates arbitrary data with an object in the registry. + * + * @param sendable object + * @param handle data handle returned by getDataHandle() + * @param data data to set + * @return Previous data (may be null) + */ + public static synchronized Object setData(Sendable sendable, int handle, Object data) { + Component comp = components.get(sendable); + if (comp == null) { + return null; + } + Object rv = null; + if (handle < comp.m_data.length) { + rv = comp.m_data[handle]; + } else if (comp.m_data == null) { + comp.m_data = new Object[handle + 1]; + } else { + comp.m_data = Arrays.copyOf(comp.m_data, handle + 1); + } + comp.m_data[handle] = data; + return rv; + } + + /** + * Gets arbitrary data associated with an object in the registry. + * + * @param sendable object + * @param handle data handle returned by getDataHandle() + * @return data (may be null if none associated) + */ + public static synchronized Object getData(Sendable sendable, int handle) { + Component comp = components.get(sendable); + if (comp == null || comp.m_data == null || handle >= comp.m_data.length) { + return null; + } + 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; + } + } + + /** + * Functional interface for foreachLiveWindow(). + */ + @FunctionalInterface + public interface LiveWindowForeachCallback { + /** + * Callback. + * + * @param sendable sendable object + * @param name name + * @param subsystem subsystem + * @param parent parent sendable object + * @param data data stored in object with setData() + * @return data to be stored back into object, or null if none/don't modify + */ + Object call(Sendable sendable, String name, String subsystem, Sendable parent, Object data); + } + + /** + * 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 pointer passed to callback + * @param callback function to call for each object + */ + @SuppressWarnings({"PMD.CyclomaticComplexity", "PMD.AvoidInstantiatingObjectsInLoops"}) + public static synchronized void foreachLiveWindow(int dataHandle, + LiveWindowForeachCallback callback) { + for (Component comp : components.values()) { + Sendable sendable = comp.m_sendable.get(); + if (sendable != null && comp.m_liveWindow) { + Sendable parent = null; + if (comp.m_parent != null) { + parent = comp.m_parent.get(); + } + Object data = null; + if (comp.m_data != null && dataHandle < comp.m_data.length) { + data = comp.m_data[dataHandle]; + } + data = callback.call(sendable, comp.m_name, comp.m_subsystem, parent, data); + if (data != null) { + if (comp.m_data == null) { + comp.m_data = new Object[dataHandle + 1]; + } else if (dataHandle >= comp.m_data.length) { + comp.m_data = Arrays.copyOf(comp.m_data, dataHandle + 1); + } + comp.m_data[dataHandle] = data; + } + } + } + } +} diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java index 08c32b2eed..50868f2818 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java @@ -97,7 +97,10 @@ public class SmartDashboard { * @throws IllegalArgumentException If key is null */ public static void putData(Sendable value) { - putData(value.getName(), value); + String name = SendableRegistry.getName(value); + if (!name.isEmpty()) { + putData(name, value); + } } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/Command.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/Command.java index 23410272c8..de87c2e117 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/Command.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/Command.java @@ -298,6 +298,11 @@ public interface Command { return false; } + /** + * Gets the name of this Command. + * + * @return Name + */ default String getName() { return this.getClass().getSimpleName(); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java index 0f706173c3..ba2c68f46f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java @@ -12,6 +12,7 @@ import java.util.Set; import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * A {@link Sendable} base class for {@link Command}s. @@ -19,10 +20,13 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; @SuppressWarnings("PMD.AbstractClassWithoutAbstractMethod") public abstract class CommandBase implements Sendable, Command { - protected String m_name = this.getClass().getSimpleName(); - protected String m_subsystem = "Ungrouped"; protected Set m_requirements = new HashSet<>(); + protected CommandBase() { + String name = getClass().getName(); + SendableRegistry.add(this, name.substring(name.lastIndexOf('.') + 1)); + } + /** * Adds the specified requirements to the command. * @@ -39,22 +43,37 @@ public abstract class CommandBase implements Sendable, Command { @Override public String getName() { - return this.getClass().getSimpleName(); + return SendableRegistry.getName(this); } + /** + * Sets the name of this Command. + * + * @param name name + */ @Override public void setName(String name) { - m_name = name; + SendableRegistry.setName(this, name); } + /** + * Gets the subsystem name of this Command. + * + * @return Subsystem name + */ @Override public String getSubsystem() { - return m_subsystem; + return SendableRegistry.getSubsystem(this); } + /** + * Sets the subsystem name of this Command. + * + * @param subsystem subsystem name + */ @Override public void setSubsystem(String subsystem) { - m_subsystem = subsystem; + SendableRegistry.setSubsystem(this, subsystem); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java index 1097811efa..13e873d7af 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java @@ -23,8 +23,9 @@ import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.wpilibj.RobotState; -import edu.wpi.first.wpilibj.SendableBase; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * The scheduler responsible for running {@link Command}s. A Command-based robot should call {@link @@ -34,7 +35,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; * Subsystem#periodic()} methods to be called and for their default commands to be scheduled. */ @SuppressWarnings({"PMD.GodClass", "PMD.TooManyMethods", "PMD.TooManyFields"}) -public final class CommandScheduler extends SendableBase { +public final class CommandScheduler implements Sendable { /** * The Singleton Instance. */ @@ -82,7 +83,7 @@ public final class CommandScheduler extends SendableBase { CommandScheduler() { HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand_Scheduler); - setName("Scheduler"); + SendableRegistry.addLW(this, "Scheduler"); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java index 55249cee6e..9ae8ae2553 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java @@ -8,8 +8,8 @@ package edu.wpi.first.wpilibj2.command; import edu.wpi.first.wpilibj.Sendable; -import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * A base for subsystems that handles registration in the constructor, and provides a more intuitive @@ -17,30 +17,54 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; */ public abstract class SubsystemBase implements Subsystem, Sendable { - protected String m_name = this.getClass().getSimpleName(); - + /** + * Constructor. + */ public SubsystemBase() { + String name = this.getClass().getSimpleName(); + name = name.substring(name.lastIndexOf('.') + 1); + SendableRegistry.addLW(this, name, name); CommandScheduler.getInstance().registerSubsystem(this); } + /** + * Gets the name of this Subsystem. + * + * @return Name + */ @Override public String getName() { - return m_name; + return SendableRegistry.getName(this); } + /** + * Sets the name of this Subsystem. + * + * @param name name + */ @Override public void setName(String name) { - m_name = name; + SendableRegistry.setName(this, name); } + /** + * Gets the subsystem name of this Subsystem. + * + * @return Subsystem name + */ @Override public String getSubsystem() { - return getName(); + return SendableRegistry.getSubsystem(this); } + /** + * Sets the subsystem name of this Subsystem. + * + * @param subsystem subsystem name + */ @Override public void setSubsystem(String subsystem) { - setName(subsystem); + SendableRegistry.setSubsystem(this, subsystem); } /** @@ -51,8 +75,8 @@ public abstract class SubsystemBase implements Subsystem, Sendable { * @param child sendable */ public void addChild(String name, Sendable child) { - child.setName(getSubsystem(), name); - LiveWindow.add(child); + SendableRegistry.addLW(child, getSubsystem(), name); + SendableRegistry.addChild(this, child); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java index 09ec2f8cd0..5e8ebc3ea3 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java @@ -8,6 +8,7 @@ package edu.wpi.first.wpilibj2.command; import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * A command that does nothing but takes a specified amount of time to finish. Useful for @@ -24,7 +25,7 @@ public class WaitCommand extends CommandBase { */ public WaitCommand(double seconds) { m_duration = seconds; - setName(m_name + ": " + seconds + " seconds"); + SendableRegistry.setName(this, getName() + ": " + seconds + " seconds"); } @Override diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java index aa2f14ef23..5bc194938f 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java @@ -50,8 +50,6 @@ class CommandParallelGroupTest extends AbstractCommandTest { Scheduler.getInstance().run(); assertCommandState(command1, 1, 3, 3, 1, 0); assertCommandState(command2, 1, 5, 5, 1, 0); - - commandGroup.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java index fbd20eab51..680a55dcc0 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java @@ -88,8 +88,6 @@ class CommandSequentialGroupTest extends AbstractCommandTest { assertCommandState(command1, 1, 1, 1, 0, 1); assertCommandState(command2, 1, 2, 2, 0, 1); assertCommandState(command3, 1, 3, 3, 1, 0); - - commandGroup.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java index 6cbeae2cf9..89ca3ec05c 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -7,16 +7,16 @@ package edu.wpi.first.wpilibj.shuffleboard; -import edu.wpi.first.wpilibj.SendableBase; +import edu.wpi.first.wpilibj.Sendable; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; /** * A mock sendable that marks itself as an actuator. */ -public class MockActuatorSendable extends SendableBase { +public class MockActuatorSendable implements Sendable { public MockActuatorSendable(String name) { - super(false); - setName(name); + SendableRegistry.add(this, name); } @Override diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java index 6a4623115f..cfe0e9f8d0 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java @@ -33,8 +33,6 @@ class CommandDecoratorTest extends CommandTestBase { scheduler.run(); assertFalse(scheduler.isScheduled(timeout)); - - scheduler.close(); } @Test @@ -51,8 +49,6 @@ class CommandDecoratorTest extends CommandTestBase { condition.setCondition(true); scheduler.run(); assertFalse(scheduler.isScheduled(command)); - - scheduler.close(); } @Test @@ -67,8 +63,6 @@ class CommandDecoratorTest extends CommandTestBase { scheduler.schedule(command.beforeStarting(() -> condition.setCondition(true))); assertTrue(condition.getCondition()); - - scheduler.close(); } @Test @@ -87,8 +81,6 @@ class CommandDecoratorTest extends CommandTestBase { scheduler.run(); assertTrue(condition.getCondition()); - - scheduler.close(); } @Test @@ -108,8 +100,6 @@ class CommandDecoratorTest extends CommandTestBase { scheduler.run(); assertTrue(condition.getCondition()); - - scheduler.close(); } @Test @@ -134,8 +124,6 @@ class CommandDecoratorTest extends CommandTestBase { scheduler.run(); assertFalse(scheduler.isScheduled(group)); - - scheduler.close(); } @Test @@ -159,8 +147,6 @@ class CommandDecoratorTest extends CommandTestBase { scheduler.run(); assertFalse(scheduler.isScheduled(group)); - - scheduler.close(); } @Test @@ -176,8 +162,6 @@ class CommandDecoratorTest extends CommandTestBase { scheduler.run(); assertFalse(scheduler.isScheduled(group)); - - scheduler.close(); } @Test @@ -194,7 +178,5 @@ class CommandDecoratorTest extends CommandTestBase { scheduler.run(); assertTrue(scheduler.isScheduled(perpetual)); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java index 7db39b64ac..b40f172754 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java @@ -41,8 +41,6 @@ class CommandGroupErrorTest extends CommandTestBase { assertThrows(IllegalArgumentException.class, () -> scheduler.schedule(command1)); - - scheduler.close(); } @Test diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java index 86eba093be..10d3ee06a7 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java @@ -41,8 +41,6 @@ class CommandRequirementsTest extends CommandTestBase { assertFalse(scheduler.isScheduled(interrupted)); assertTrue(scheduler.isScheduled(interrupter)); - - scheduler.close(); } @Test @@ -61,8 +59,6 @@ class CommandRequirementsTest extends CommandTestBase { assertTrue(scheduler.isScheduled(notInterrupted)); assertFalse(scheduler.isScheduled(interrupter)); - - scheduler.close(); } @Test @@ -79,7 +75,5 @@ class CommandRequirementsTest extends CommandTestBase { () -> scheduler.setDefaultCommand(system, missingRequirement)); assertThrows(IllegalArgumentException.class, () -> scheduler.setDefaultCommand(system, ends)); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java index c5178791a7..aee30db89e 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java @@ -35,8 +35,6 @@ class CommandScheduleTest extends CommandTestBase { verify(mockCommand).end(false); assertFalse(scheduler.isScheduled(mockCommand)); - - scheduler.close(); } @Test @@ -59,8 +57,6 @@ class CommandScheduleTest extends CommandTestBase { verify(mockCommand).end(false); assertFalse(scheduler.isScheduled(mockCommand)); - - scheduler.close(); } @Test @@ -92,8 +88,6 @@ class CommandScheduleTest extends CommandTestBase { command3Holder.setFinished(true); scheduler.run(); assertFalse(scheduler.isScheduled(command1, command2, command3)); - - scheduler.close(); } @Test @@ -114,8 +108,6 @@ class CommandScheduleTest extends CommandTestBase { verify(mockCommand, never()).end(false); assertFalse(scheduler.isScheduled(mockCommand)); - - scheduler.close(); } @Test @@ -126,7 +118,5 @@ class CommandScheduleTest extends CommandTestBase { Command mockCommand = holder.getMock(); assertDoesNotThrow(() -> scheduler.cancel(mockCommand)); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java index 73f34c357f..0740565b71 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java @@ -36,8 +36,6 @@ class ConditionalCommandTest extends CommandTestBase { verify(command2, never()).initialize(); verify(command2, never()).execute(); verify(command2, never()).end(false); - - scheduler.close(); } @Test @@ -63,7 +61,5 @@ class ConditionalCommandTest extends CommandTestBase { verify(command1).end(true); verify(command2, never()).end(true); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java index 36ee0a472a..033dcc5e43 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java @@ -27,8 +27,6 @@ class DefaultCommandTest extends CommandTestBase { scheduler.run(); assertTrue(scheduler.isScheduled(defaultCommand)); - - scheduler.close(); } @Test @@ -54,8 +52,6 @@ class DefaultCommandTest extends CommandTestBase { assertTrue(scheduler.isScheduled(defaultCommand)); assertFalse(scheduler.isScheduled(interrupter)); - - scheduler.close(); } @Test @@ -83,7 +79,5 @@ class DefaultCommandTest extends CommandTestBase { assertTrue(scheduler.isScheduled(defaultCommand)); verify(defaultCommand).end(true); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java index 8e2edb842a..23f508a339 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java @@ -39,7 +39,5 @@ class FunctionalCommandTest extends CommandTestBase { assertTrue(cond1.getCondition()); assertTrue(cond2.getCondition()); assertTrue(cond3.getCondition()); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java index daa35725b4..a109ed65c6 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java @@ -26,7 +26,5 @@ class InstantCommandTest extends CommandTestBase { assertTrue(cond.getCondition()); assertFalse(scheduler.isScheduled(command)); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java index 84032a1fc0..1bed736f18 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java @@ -30,7 +30,5 @@ class NotifierCommandTest extends CommandTestBase { scheduler.cancel(command); assertEquals(.25, 0.01 * counter.m_counter, .025); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java index 719fe9de54..d03b4aa4dd 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java @@ -45,8 +45,6 @@ class ParallelCommandGroupTest extends CommandTestBase { verify(command2).end(false); assertFalse(scheduler.isScheduled(group)); - - scheduler.close(); } @Test @@ -75,8 +73,6 @@ class ParallelCommandGroupTest extends CommandTestBase { verify(command2).end(true); assertFalse(scheduler.isScheduled(group)); - - scheduler.close(); } @Test @@ -91,8 +87,6 @@ class ParallelCommandGroupTest extends CommandTestBase { Command group = new ParallelCommandGroup(command1, command2); assertDoesNotThrow(() -> scheduler.cancel(group)); - - scheduler.close(); } @Test @@ -118,8 +112,6 @@ class ParallelCommandGroupTest extends CommandTestBase { assertFalse(scheduler.isScheduled(group)); assertTrue(scheduler.isScheduled(command3)); - - scheduler.close(); } @Test diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java index 13a8f14ddd..c7e3769f51 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java @@ -55,8 +55,6 @@ class ParallelDeadlineGroupTest extends CommandTestBase { verify(command3, times(2)).execute(); verify(command3, never()).end(false); verify(command3).end(true); - - scheduler.close(); } @Test @@ -86,8 +84,6 @@ class ParallelDeadlineGroupTest extends CommandTestBase { verify(command2, never()).end(true); assertFalse(scheduler.isScheduled(group)); - - scheduler.close(); } @@ -114,8 +110,6 @@ class ParallelDeadlineGroupTest extends CommandTestBase { assertFalse(scheduler.isScheduled(group)); assertTrue(scheduler.isScheduled(command3)); - - scheduler.close(); } @Test diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java index 40c7439c19..c9b21e4bad 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java @@ -46,8 +46,6 @@ class ParallelRaceGroupTest extends CommandTestBase { verify(command2, never()).end(false); assertFalse(scheduler.isScheduled(group)); - - scheduler.close(); } @Test @@ -76,8 +74,6 @@ class ParallelRaceGroupTest extends CommandTestBase { verify(command2).end(true); assertFalse(scheduler.isScheduled(group)); - - scheduler.close(); } @Test @@ -92,8 +88,6 @@ class ParallelRaceGroupTest extends CommandTestBase { Command group = new ParallelRaceGroup(command1, command2); assertDoesNotThrow(() -> scheduler.cancel(group)); - - scheduler.close(); } @@ -120,8 +114,6 @@ class ParallelRaceGroupTest extends CommandTestBase { assertFalse(scheduler.isScheduled(group)); assertTrue(scheduler.isScheduled(command3)); - - scheduler.close(); } @Test diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/PerpetualCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/PerpetualCommandTest.java index 9c835478a6..baf037f5cc 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/PerpetualCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/PerpetualCommandTest.java @@ -22,7 +22,5 @@ class PerpetualCommandTest extends CommandTestBase { scheduler.run(); assertTrue(scheduler.isScheduled(command)); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/PrintCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/PrintCommandTest.java index c710d2a151..7484396268 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/PrintCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/PrintCommandTest.java @@ -33,7 +33,5 @@ class PrintCommandTest extends CommandTestBase { assertEquals(testOut.toString(), "Test!" + System.lineSeparator()); System.setOut(originalOut); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommandTest.java index 21133b0cdc..b566aae568 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommandTest.java @@ -26,8 +26,6 @@ class ProxyScheduleCommandTest extends CommandTestBase { scheduler.schedule(scheduleCommand); verify(command1).schedule(); - - scheduler.close(); } @Test @@ -49,7 +47,5 @@ class ProxyScheduleCommandTest extends CommandTestBase { scheduler.run(); scheduler.run(); assertFalse(scheduler.isScheduled(scheduleCommand)); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java index 428283d130..e862216c5e 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java @@ -34,8 +34,6 @@ class RobotDisabledCommandTest extends CommandTestBase { assertFalse(scheduler.isScheduled(mockCommand)); setDSEnabled(true); - - scheduler.close(); } @Test @@ -54,8 +52,6 @@ class RobotDisabledCommandTest extends CommandTestBase { scheduler.run(); assertTrue(scheduler.isScheduled(mockCommand)); - - scheduler.close(); } @Test @@ -83,8 +79,6 @@ class RobotDisabledCommandTest extends CommandTestBase { assertTrue(scheduler.isScheduled(runWhenDisabled)); assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); - - scheduler.close(); } @Test @@ -112,8 +106,6 @@ class RobotDisabledCommandTest extends CommandTestBase { assertTrue(scheduler.isScheduled(runWhenDisabled)); assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); - - scheduler.close(); } @Test @@ -138,8 +130,6 @@ class RobotDisabledCommandTest extends CommandTestBase { assertTrue(scheduler.isScheduled(runWhenDisabled)); assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); - - scheduler.close(); } @Test @@ -164,8 +154,6 @@ class RobotDisabledCommandTest extends CommandTestBase { assertTrue(scheduler.isScheduled(runWhenDisabled)); assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); - - scheduler.close(); } @Test @@ -191,7 +179,5 @@ class RobotDisabledCommandTest extends CommandTestBase { scheduler.schedule(parallel); assertFalse(scheduler.isScheduled(runWhenDisabled)); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java index 41d16b3457..3ff8c3dfdf 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java @@ -26,7 +26,5 @@ class RunCommandTest extends CommandTestBase { scheduler.run(); assertEquals(3, counter.m_counter); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java index c9bec76d90..0a5035233b 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java @@ -27,7 +27,5 @@ class ScheduleCommandTest extends CommandTestBase { verify(command1).schedule(); verify(command2).schedule(); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java index 9ee91748ba..1f110b68ed 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java @@ -27,8 +27,6 @@ class SchedulerTest extends CommandTestBase { scheduler.run(); assertEquals(counter.m_counter, 3); - - scheduler.close(); } @Test @@ -45,8 +43,6 @@ class SchedulerTest extends CommandTestBase { scheduler.cancel(command); assertEquals(counter.m_counter, 1); - - scheduler.close(); } @Test @@ -57,7 +53,5 @@ class SchedulerTest extends CommandTestBase { scheduler.registerSubsystem(system); assertDoesNotThrow(() -> scheduler.unregisterSubsystem(system)); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java index 74cbc099e3..df52855f46 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java @@ -50,8 +50,6 @@ class SelectCommandTest extends CommandTestBase { verify(command3, never()).initialize(); verify(command3, never()).execute(); verify(command3, never()).end(false); - - scheduler.close(); } @Test @@ -74,8 +72,6 @@ class SelectCommandTest extends CommandTestBase { () -> "four"); assertDoesNotThrow(() -> scheduler.schedule(selectCommand)); - - scheduler.close(); } @@ -108,7 +104,5 @@ class SelectCommandTest extends CommandTestBase { verify(command1).end(true); verify(command2, never()).end(true); verify(command3, never()).end(true); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java index 680f826d48..8582140547 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java @@ -50,8 +50,6 @@ class SequentialCommandGroupTest extends CommandTestBase { verify(command2).end(false); assertFalse(scheduler.isScheduled(group)); - - scheduler.close(); } @Test @@ -86,8 +84,6 @@ class SequentialCommandGroupTest extends CommandTestBase { verify(command3, never()).end(false); assertFalse(scheduler.isScheduled(group)); - - scheduler.close(); } @Test @@ -102,8 +98,6 @@ class SequentialCommandGroupTest extends CommandTestBase { Command group = new SequentialCommandGroup(command1, command2); assertDoesNotThrow(() -> scheduler.cancel(group)); - - scheduler.close(); } @@ -130,7 +124,5 @@ class SequentialCommandGroupTest extends CommandTestBase { assertFalse(scheduler.isScheduled(group)); assertTrue(scheduler.isScheduled(command3)); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java index c8d1dd1117..93921e04e2 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java @@ -33,7 +33,5 @@ class StartEndCommandTest extends CommandTestBase { assertFalse(scheduler.isScheduled(command)); assertTrue(cond1.getCondition()); assertTrue(cond2.getCondition()); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/WaitCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/WaitCommandTest.java index 9926557f09..5a522af28d 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/WaitCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/WaitCommandTest.java @@ -37,8 +37,6 @@ class WaitCommandTest extends CommandTestBase { scheduler.run(); assertFalse(scheduler.isScheduled(waitCommand)); - - scheduler.close(); } @Test @@ -65,7 +63,5 @@ class WaitCommandTest extends CommandTestBase { verify(command1).end(true); verify(command1, never()).end(false); assertFalse(scheduler.isScheduled(timeout)); - - scheduler.close(); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java index 3df023320c..a99a18cac5 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java @@ -27,7 +27,5 @@ class WaitUntilCommandTest extends CommandTestBase { condition.setCondition(true); scheduler.run(); assertFalse(scheduler.isScheduled(command)); - - scheduler.close(); } } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Collector.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Collector.java index 6bff9ff24f..853b51a941 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Collector.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Collector.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -18,7 +18,7 @@ import edu.wpi.first.wpilibj.command.Subsystem; * ball detection, a piston for opening and closing the claw, and a reed switch * to check if the piston is open. */ -public class Collector extends Subsystem { +public class Collector extends Subsystem implements AutoCloseable { // Constants for some useful speeds public static final double kForward = 1; public static final double kStop = 0; diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java index b5af375310..de08259f32 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java @@ -193,7 +193,6 @@ public class MotorEncoderTest extends AbstractComsSetup { .getPositionError(), pidController.atSetpoint()); pidRunner.close(); - pidController.close(); } @Test @@ -214,7 +213,6 @@ public class MotorEncoderTest extends AbstractComsSetup { .getPositionError(), pidController.atSetpoint()); pidRunner.close(); - pidController.close(); } /** diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java index e73f716e76..2c1eac18f5 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java @@ -63,8 +63,6 @@ public class PCMTest extends AbstractComsSetup { @AfterClass public static void tearDownAfterClass() { - compressor.close(); - fakePressureSwitch.close(); fakeCompressor.close(); diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java index 580c866b41..bbb034e123 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java @@ -47,7 +47,6 @@ public class PDPTest extends AbstractComsSetup { @AfterClass public static void tearDownAfterClass() { - pdp.close(); pdp = null; me.teardown(); me = null; diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java index d366e218d8..601fff5f00 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java @@ -112,7 +112,6 @@ public class PIDTest extends AbstractComsSetup { @After public void tearDown() { logger.fine("Teardown: " + me.getType()); - m_controller.close(); m_controller = null; me.reset(); }