From 6b168ab0c8bc83530b3641a37e6af3df16dc4b1b Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Fri, 12 Mar 2021 15:41:52 -0800 Subject: [PATCH] [wpilib] Remove PIDController, PIDOutput, PIDSource Move them to the old commands vendordep so that PIDCommand and PIDSubsystem continue to work. This also removes Filter and LinearDigitalFilter. --- .../java/edu/wpi/first/wpilibj/PIDBase.java | 0 .../edu/wpi/first/wpilibj/PIDController.java | 0 .../edu/wpi/first/wpilibj/PIDInterface.java | 0 .../java/edu/wpi/first/wpilibj/PIDOutput.java | 0 .../java/edu/wpi/first/wpilibj/PIDSource.java | 0 .../edu/wpi/first/wpilibj/PIDSourceType.java | 0 .../src/main/native/cpp/PIDBase.cpp | 0 .../src/main/native/cpp/PIDController.cpp | 0 .../src/main/native/cpp/PIDSource.cpp | 0 .../src/main/native/include/frc/PIDBase.h | 0 .../main/native/include/frc/PIDController.h | 0 .../main/native/include/frc/PIDInterface.h | 0 .../src/main/native/include/frc/PIDOutput.h | 0 .../src/main/native/include/frc/PIDSource.h | 0 .../main/native/cpp/AnalogAccelerometer.cpp | 4 - wpilibc/src/main/native/cpp/AnalogInput.cpp | 7 - .../main/native/cpp/AnalogPotentiometer.cpp | 4 - wpilibc/src/main/native/cpp/Encoder.cpp | 14 -- wpilibc/src/main/native/cpp/GyroBase.cpp | 11 - .../src/main/native/cpp/NidecBrushless.cpp | 4 - .../main/native/cpp/PWMSpeedController.cpp | 4 - .../main/native/cpp/SpeedControllerGroup.cpp | 4 - wpilibc/src/main/native/cpp/Ultrasonic.cpp | 41 +--- .../src/main/native/cpp/filters/Filter.cpp | 27 --- .../cpp/filters/LinearDigitalFilter.cpp | 133 ----------- .../native/cpp/interfaces/Potentiometer.cpp | 15 -- .../native/include/frc/AnalogAccelerometer.h | 9 - .../src/main/native/include/frc/AnalogInput.h | 9 - .../native/include/frc/AnalogPotentiometer.h | 7 - wpilibc/src/main/native/include/frc/Encoder.h | 4 - .../src/main/native/include/frc/GyroBase.h | 11 - .../main/native/include/frc/NidecBrushless.h | 8 - .../native/include/frc/PWMSpeedController.h | 7 - .../main/native/include/frc/SpeedController.h | 4 +- .../native/include/frc/SpeedControllerGroup.h | 1 - .../src/main/native/include/frc/Ultrasonic.h | 44 +--- .../include/frc/controller/PIDController.h | 6 + .../main/native/include/frc/filters/Filter.h | 61 ----- .../include/frc/filters/LinearDigitalFilter.h | 223 ------------------ .../include/frc/interfaces/Potentiometer.h | 8 +- .../test/native/cpp/MockSpeedController.cpp | 4 - .../native/cpp/SpeedControllerGroupTest.cpp | 8 - .../test/native/include/MockSpeedController.h | 2 - .../include/ExampleSmartMotorController.h | 2 - .../include/ExampleSmartMotorController.h | 2 - .../include/ExampleSmartMotorController.h | 2 - .../PacGoat/cpp/subsystems/DriveTrain.cpp | 4 - .../examples/PacGoat/cpp/subsystems/Pivot.cpp | 2 +- .../first/wpilibj/AnalogAccelerometer.java | 23 +- .../edu/wpi/first/wpilibj/AnalogInput.java | 23 +- .../first/wpilibj/AnalogPotentiometer.java | 24 -- .../java/edu/wpi/first/wpilibj/Counter.java | 36 +-- .../java/edu/wpi/first/wpilibj/Encoder.java | 38 +-- .../java/edu/wpi/first/wpilibj/GyroBase.java | 38 +-- .../edu/wpi/first/wpilibj/NidecBrushless.java | 10 - .../wpi/first/wpilibj/PWMSpeedController.java | 10 - .../wpi/first/wpilibj/SpeedController.java | 3 +- .../first/wpilibj/SpeedControllerGroup.java | 5 - .../edu/wpi/first/wpilibj/Ultrasonic.java | 95 +------- .../edu/wpi/first/wpilibj/filters/Filter.java | 54 ----- .../wpilibj/filters/LinearDigitalFilter.java | 187 --------------- .../wpilibj/interfaces/Potentiometer.java | 4 +- .../first/wpilibj/MockSpeedController.java | 5 - .../wpilibj/SpeedControllerGroupTest.java | 11 - .../ExampleSmartMotorController.java | 3 - .../ExampleSmartMotorController.java | 3 - .../ExampleSmartMotorController.java | 3 - .../examples/pacgoat/subsystems/Pivot.java | 2 +- .../first/wpilibj/MockSpeedController.java | 5 - 69 files changed, 30 insertions(+), 1248 deletions(-) rename {wpilibj => wpilibOldCommands}/src/main/java/edu/wpi/first/wpilibj/PIDBase.java (100%) rename {wpilibj => wpilibOldCommands}/src/main/java/edu/wpi/first/wpilibj/PIDController.java (100%) rename {wpilibj => wpilibOldCommands}/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java (100%) rename {wpilibj => wpilibOldCommands}/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java (100%) rename {wpilibj => wpilibOldCommands}/src/main/java/edu/wpi/first/wpilibj/PIDSource.java (100%) rename {wpilibj => wpilibOldCommands}/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java (100%) rename {wpilibc => wpilibOldCommands}/src/main/native/cpp/PIDBase.cpp (100%) rename {wpilibc => wpilibOldCommands}/src/main/native/cpp/PIDController.cpp (100%) rename {wpilibc => wpilibOldCommands}/src/main/native/cpp/PIDSource.cpp (100%) rename {wpilibc => wpilibOldCommands}/src/main/native/include/frc/PIDBase.h (100%) rename {wpilibc => wpilibOldCommands}/src/main/native/include/frc/PIDController.h (100%) rename {wpilibc => wpilibOldCommands}/src/main/native/include/frc/PIDInterface.h (100%) rename {wpilibc => wpilibOldCommands}/src/main/native/include/frc/PIDOutput.h (100%) rename {wpilibc => wpilibOldCommands}/src/main/native/include/frc/PIDSource.h (100%) delete mode 100644 wpilibc/src/main/native/cpp/filters/Filter.cpp delete mode 100644 wpilibc/src/main/native/cpp/filters/LinearDigitalFilter.cpp delete mode 100644 wpilibc/src/main/native/cpp/interfaces/Potentiometer.cpp delete mode 100644 wpilibc/src/main/native/include/frc/filters/Filter.h delete mode 100644 wpilibc/src/main/native/include/frc/filters/LinearDigitalFilter.h delete mode 100644 wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/Filter.java delete mode 100644 wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/LinearDigitalFilter.java diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java similarity index 100% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java rename to wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDController.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDController.java similarity index 100% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDController.java rename to wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDController.java diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java similarity index 100% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java rename to wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java similarity index 100% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java rename to wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDSource.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSource.java similarity index 100% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDSource.java rename to wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSource.java diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java similarity index 100% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java rename to wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java diff --git a/wpilibc/src/main/native/cpp/PIDBase.cpp b/wpilibOldCommands/src/main/native/cpp/PIDBase.cpp similarity index 100% rename from wpilibc/src/main/native/cpp/PIDBase.cpp rename to wpilibOldCommands/src/main/native/cpp/PIDBase.cpp diff --git a/wpilibc/src/main/native/cpp/PIDController.cpp b/wpilibOldCommands/src/main/native/cpp/PIDController.cpp similarity index 100% rename from wpilibc/src/main/native/cpp/PIDController.cpp rename to wpilibOldCommands/src/main/native/cpp/PIDController.cpp diff --git a/wpilibc/src/main/native/cpp/PIDSource.cpp b/wpilibOldCommands/src/main/native/cpp/PIDSource.cpp similarity index 100% rename from wpilibc/src/main/native/cpp/PIDSource.cpp rename to wpilibOldCommands/src/main/native/cpp/PIDSource.cpp diff --git a/wpilibc/src/main/native/include/frc/PIDBase.h b/wpilibOldCommands/src/main/native/include/frc/PIDBase.h similarity index 100% rename from wpilibc/src/main/native/include/frc/PIDBase.h rename to wpilibOldCommands/src/main/native/include/frc/PIDBase.h diff --git a/wpilibc/src/main/native/include/frc/PIDController.h b/wpilibOldCommands/src/main/native/include/frc/PIDController.h similarity index 100% rename from wpilibc/src/main/native/include/frc/PIDController.h rename to wpilibOldCommands/src/main/native/include/frc/PIDController.h diff --git a/wpilibc/src/main/native/include/frc/PIDInterface.h b/wpilibOldCommands/src/main/native/include/frc/PIDInterface.h similarity index 100% rename from wpilibc/src/main/native/include/frc/PIDInterface.h rename to wpilibOldCommands/src/main/native/include/frc/PIDInterface.h diff --git a/wpilibc/src/main/native/include/frc/PIDOutput.h b/wpilibOldCommands/src/main/native/include/frc/PIDOutput.h similarity index 100% rename from wpilibc/src/main/native/include/frc/PIDOutput.h rename to wpilibOldCommands/src/main/native/include/frc/PIDOutput.h diff --git a/wpilibc/src/main/native/include/frc/PIDSource.h b/wpilibOldCommands/src/main/native/include/frc/PIDSource.h similarity index 100% rename from wpilibc/src/main/native/include/frc/PIDSource.h rename to wpilibOldCommands/src/main/native/include/frc/PIDSource.h diff --git a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp index fa8654076a..e0e3ef71ac 100644 --- a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp +++ b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp @@ -48,10 +48,6 @@ void AnalogAccelerometer::SetZero(double zero) { m_zeroGVoltage = zero; } -double AnalogAccelerometer::PIDGet() { - return GetAcceleration(); -} - void AnalogAccelerometer::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Accelerometer"); builder.AddDoubleProperty( diff --git a/wpilibc/src/main/native/cpp/AnalogInput.cpp b/wpilibc/src/main/native/cpp/AnalogInput.cpp index b67120dbf2..9c6d0c2deb 100644 --- a/wpilibc/src/main/native/cpp/AnalogInput.cpp +++ b/wpilibc/src/main/native/cpp/AnalogInput.cpp @@ -254,13 +254,6 @@ double AnalogInput::GetSampleRate() { return sampleRate; } -double AnalogInput::PIDGet() { - if (StatusIsFatal()) { - return 0.0; - } - return GetAverageVoltage(); -} - void AnalogInput::SetSimDevice(HAL_SimDeviceHandle device) { HAL_SetAnalogInputSimDevice(m_port, device); } diff --git a/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp b/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp index b911285bb1..8237658dbc 100644 --- a/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp +++ b/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp @@ -42,10 +42,6 @@ double AnalogPotentiometer::Get() const { m_offset; } -double AnalogPotentiometer::PIDGet() { - return Get(); -} - void AnalogPotentiometer::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Analog Input"); builder.AddDoubleProperty( diff --git a/wpilibc/src/main/native/cpp/Encoder.cpp b/wpilibc/src/main/native/cpp/Encoder.cpp index 57e58590af..2d7373940b 100644 --- a/wpilibc/src/main/native/cpp/Encoder.cpp +++ b/wpilibc/src/main/native/cpp/Encoder.cpp @@ -213,20 +213,6 @@ int Encoder::GetSamplesToAverage() const { return result; } -double Encoder::PIDGet() { - if (StatusIsFatal()) { - return 0.0; - } - switch (GetPIDSourceType()) { - case PIDSourceType::kDisplacement: - return GetDistance(); - case PIDSourceType::kRate: - return GetRate(); - default: - return 0.0; - } -} - void Encoder::SetIndexSource(int channel, Encoder::IndexingType type) { // Force digital input if just given an index m_indexSource = std::make_shared(channel); diff --git a/wpilibc/src/main/native/cpp/GyroBase.cpp b/wpilibc/src/main/native/cpp/GyroBase.cpp index 9aeb10cb98..bcb25fad13 100644 --- a/wpilibc/src/main/native/cpp/GyroBase.cpp +++ b/wpilibc/src/main/native/cpp/GyroBase.cpp @@ -9,17 +9,6 @@ using namespace frc; -double GyroBase::PIDGet() { - switch (GetPIDSourceType()) { - case PIDSourceType::kRate: - return GetRate(); - case PIDSourceType::kDisplacement: - return GetAngle(); - default: - return 0; - } -} - void GyroBase::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Gyro"); builder.AddDoubleProperty( diff --git a/wpilibc/src/main/native/cpp/NidecBrushless.cpp b/wpilibc/src/main/native/cpp/NidecBrushless.cpp index 4909a01e31..ff61843000 100644 --- a/wpilibc/src/main/native/cpp/NidecBrushless.cpp +++ b/wpilibc/src/main/native/cpp/NidecBrushless.cpp @@ -59,10 +59,6 @@ void NidecBrushless::Enable() { m_disabled = false; } -void NidecBrushless::PIDWrite(double output) { - Set(output); -} - void NidecBrushless::StopMotor() { m_dio.UpdateDutyCycle(0.5); m_pwm.SetDisabled(); diff --git a/wpilibc/src/main/native/cpp/PWMSpeedController.cpp b/wpilibc/src/main/native/cpp/PWMSpeedController.cpp index 6012301874..ff04282559 100644 --- a/wpilibc/src/main/native/cpp/PWMSpeedController.cpp +++ b/wpilibc/src/main/native/cpp/PWMSpeedController.cpp @@ -42,10 +42,6 @@ int PWMSpeedController::GetChannel() const { return m_pwm.GetChannel(); } -void PWMSpeedController::PIDWrite(double output) { - Set(output); -} - PWMSpeedController::PWMSpeedController(const wpi::Twine& name, int channel) : m_pwm(channel, false) { SendableRegistry::GetInstance().AddLW(this, name, channel); diff --git a/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp b/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp index ce9aa32203..a9976d74a3 100644 --- a/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp +++ b/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp @@ -60,10 +60,6 @@ void SpeedControllerGroup::StopMotor() { } } -void SpeedControllerGroup::PIDWrite(double output) { - Set(output); -} - void SpeedControllerGroup::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Speed Controller"); builder.SetActuator(true); diff --git a/wpilibc/src/main/native/cpp/Ultrasonic.cpp b/wpilibc/src/main/native/cpp/Ultrasonic.cpp index dd34fe8553..140c66ae5b 100644 --- a/wpilibc/src/main/native/cpp/Ultrasonic.cpp +++ b/wpilibc/src/main/native/cpp/Ultrasonic.cpp @@ -26,47 +26,39 @@ std::atomic Ultrasonic::m_automaticEnabled{false}; std::vector Ultrasonic::m_sensors; std::thread Ultrasonic::m_thread; -Ultrasonic::Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units) +Ultrasonic::Ultrasonic(int pingChannel, int echoChannel) : m_pingChannel(std::make_shared(pingChannel)), m_echoChannel(std::make_shared(echoChannel)), m_counter(m_echoChannel) { - m_units = units; Initialize(); auto& registry = SendableRegistry::GetInstance(); registry.AddChild(this, m_pingChannel.get()); registry.AddChild(this, m_echoChannel.get()); } -Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel, - DistanceUnit units) +Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel) : m_pingChannel(pingChannel, NullDeleter()), m_echoChannel(echoChannel, NullDeleter()), m_counter(m_echoChannel) { if (pingChannel == nullptr || echoChannel == nullptr) { wpi_setWPIError(NullParameter); - m_units = units; return; } - m_units = units; Initialize(); } -Ultrasonic::Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel, - DistanceUnit units) +Ultrasonic::Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel) : m_pingChannel(&pingChannel, NullDeleter()), m_echoChannel(&echoChannel, NullDeleter()), m_counter(m_echoChannel) { - m_units = units; Initialize(); } Ultrasonic::Ultrasonic(std::shared_ptr pingChannel, - std::shared_ptr echoChannel, - DistanceUnit units) + std::shared_ptr echoChannel) : m_pingChannel(std::move(pingChannel)), m_echoChannel(std::move(echoChannel)), m_counter(m_echoChannel) { - m_units = units; Initialize(); } @@ -164,31 +156,6 @@ void Ultrasonic::SetEnabled(bool enable) { m_enabled = enable; } -void Ultrasonic::SetDistanceUnits(DistanceUnit units) { - m_units = units; -} - -Ultrasonic::DistanceUnit Ultrasonic::GetDistanceUnits() const { - return m_units; -} - -double Ultrasonic::PIDGet() { - switch (m_units) { - case Ultrasonic::kInches: - return GetRangeInches(); - case Ultrasonic::kMilliMeters: - return GetRangeMM(); - default: - return 0.0; - } -} - -void Ultrasonic::SetPIDSourceType(PIDSourceType pidSource) { - if (wpi_assert(pidSource == PIDSourceType::kDisplacement)) { - m_pidSource = pidSource; - } -} - void Ultrasonic::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Ultrasonic"); builder.AddDoubleProperty( diff --git a/wpilibc/src/main/native/cpp/filters/Filter.cpp b/wpilibc/src/main/native/cpp/filters/Filter.cpp deleted file mode 100644 index 1676c94894..0000000000 --- a/wpilibc/src/main/native/cpp/filters/Filter.cpp +++ /dev/null @@ -1,27 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "frc/filters/Filter.h" - -#include "frc/Base.h" - -using namespace frc; - -Filter::Filter(PIDSource& source) - : m_source(std::shared_ptr(&source, NullDeleter())) {} - -Filter::Filter(std::shared_ptr source) - : m_source(std::move(source)) {} - -void Filter::SetPIDSourceType(PIDSourceType pidSource) { - m_source->SetPIDSourceType(pidSource); -} - -PIDSourceType Filter::GetPIDSourceType() const { - return m_source->GetPIDSourceType(); -} - -double Filter::PIDGetSource() { - return m_source->PIDGet(); -} diff --git a/wpilibc/src/main/native/cpp/filters/LinearDigitalFilter.cpp b/wpilibc/src/main/native/cpp/filters/LinearDigitalFilter.cpp deleted file mode 100644 index c4b48f6783..0000000000 --- a/wpilibc/src/main/native/cpp/filters/LinearDigitalFilter.cpp +++ /dev/null @@ -1,133 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "frc/filters/LinearDigitalFilter.h" - -#include -#include - -#include - -using namespace frc; - -LinearDigitalFilter::LinearDigitalFilter(PIDSource& source, - wpi::ArrayRef ffGains, - wpi::ArrayRef fbGains) - : Filter(source), - m_inputs(ffGains.size()), - m_outputs(fbGains.size()), - m_inputGains(ffGains), - m_outputGains(fbGains) { - static int instances = 0; - instances++; - HAL_Report(HALUsageReporting::kResourceType_LinearFilter, instances); -} - -LinearDigitalFilter::LinearDigitalFilter(PIDSource& source, - std::initializer_list ffGains, - std::initializer_list fbGains) - : LinearDigitalFilter(source, - wpi::makeArrayRef(ffGains.begin(), ffGains.end()), - wpi::makeArrayRef(fbGains.begin(), fbGains.end())) {} - -LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr source, - wpi::ArrayRef ffGains, - wpi::ArrayRef fbGains) - : Filter(source), - m_inputs(ffGains.size()), - m_outputs(fbGains.size()), - m_inputGains(ffGains), - m_outputGains(fbGains) { - static int instances = 0; - instances++; - HAL_Report(HALUsageReporting::kResourceType_LinearFilter, instances); -} - -LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr source, - std::initializer_list ffGains, - std::initializer_list fbGains) - : LinearDigitalFilter(source, - wpi::makeArrayRef(ffGains.begin(), ffGains.end()), - wpi::makeArrayRef(fbGains.begin(), fbGains.end())) {} - -LinearDigitalFilter LinearDigitalFilter::SinglePoleIIR(PIDSource& source, - double timeConstant, - double period) { - double gain = std::exp(-period / timeConstant); - return LinearDigitalFilter(source, {1.0 - gain}, {-gain}); -} - -LinearDigitalFilter LinearDigitalFilter::HighPass(PIDSource& source, - double timeConstant, - double period) { - double gain = std::exp(-period / timeConstant); - return LinearDigitalFilter(source, {gain, -gain}, {-gain}); -} - -LinearDigitalFilter LinearDigitalFilter::MovingAverage(PIDSource& source, - int taps) { - assert(taps > 0); - - std::vector gains(taps, 1.0 / taps); - return LinearDigitalFilter(source, gains, {}); -} - -LinearDigitalFilter LinearDigitalFilter::SinglePoleIIR( - std::shared_ptr source, double timeConstant, double period) { - double gain = std::exp(-period / timeConstant); - return LinearDigitalFilter(std::move(source), {1.0 - gain}, {-gain}); -} - -LinearDigitalFilter LinearDigitalFilter::HighPass( - std::shared_ptr source, double timeConstant, double period) { - double gain = std::exp(-period / timeConstant); - return LinearDigitalFilter(std::move(source), {gain, -gain}, {-gain}); -} - -LinearDigitalFilter LinearDigitalFilter::MovingAverage( - std::shared_ptr source, int taps) { - assert(taps > 0); - - std::vector gains(taps, 1.0 / taps); - return LinearDigitalFilter(std::move(source), gains, {}); -} - -double LinearDigitalFilter::Get() const { - double retVal = 0.0; - - // Calculate the new value - for (size_t i = 0; i < m_inputGains.size(); i++) { - retVal += m_inputs[i] * m_inputGains[i]; - } - for (size_t i = 0; i < m_outputGains.size(); i++) { - retVal -= m_outputs[i] * m_outputGains[i]; - } - - return retVal; -} - -void LinearDigitalFilter::Reset() { - m_inputs.reset(); - m_outputs.reset(); -} - -double LinearDigitalFilter::PIDGet() { - double retVal = 0.0; - - // Rotate the inputs - m_inputs.push_front(PIDGetSource()); - - // Calculate the new value - for (size_t i = 0; i < m_inputGains.size(); i++) { - retVal += m_inputs[i] * m_inputGains[i]; - } - for (size_t i = 0; i < m_outputGains.size(); i++) { - retVal -= m_outputs[i] * m_outputGains[i]; - } - - // Rotate the outputs - m_outputs.push_front(retVal); - - return retVal; -} diff --git a/wpilibc/src/main/native/cpp/interfaces/Potentiometer.cpp b/wpilibc/src/main/native/cpp/interfaces/Potentiometer.cpp deleted file mode 100644 index 9b412213b5..0000000000 --- a/wpilibc/src/main/native/cpp/interfaces/Potentiometer.cpp +++ /dev/null @@ -1,15 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "frc/interfaces/Potentiometer.h" - -#include "frc/Utility.h" - -using namespace frc; - -void Potentiometer::SetPIDSourceType(PIDSourceType pidSource) { - if (wpi_assert(pidSource == PIDSourceType::kDisplacement)) { - m_pidSource = pidSource; - } -} diff --git a/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h b/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h index 96b9598c74..f157cd5d6a 100644 --- a/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h +++ b/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h @@ -8,7 +8,6 @@ #include "frc/AnalogInput.h" #include "frc/ErrorBase.h" -#include "frc/PIDSource.h" #include "frc/smartdashboard/Sendable.h" #include "frc/smartdashboard/SendableHelper.h" @@ -24,7 +23,6 @@ class SendableBuilder; * calibrated by finding the center value over a period of time. */ class AnalogAccelerometer : public ErrorBase, - public PIDSource, public Sendable, public SendableHelper { public: @@ -97,13 +95,6 @@ class AnalogAccelerometer : public ErrorBase, */ void SetZero(double zero); - /** - * Get the Acceleration for the PID Source parent. - * - * @return The current acceleration in Gs. - */ - double PIDGet() override; - void InitSendable(SendableBuilder& builder) override; private: diff --git a/wpilibc/src/main/native/include/frc/AnalogInput.h b/wpilibc/src/main/native/include/frc/AnalogInput.h index e9cb320ccc..7a9ebeeb6d 100644 --- a/wpilibc/src/main/native/include/frc/AnalogInput.h +++ b/wpilibc/src/main/native/include/frc/AnalogInput.h @@ -9,7 +9,6 @@ #include #include "frc/ErrorBase.h" -#include "frc/PIDSource.h" #include "frc/smartdashboard/Sendable.h" #include "frc/smartdashboard/SendableHelper.h" @@ -32,7 +31,6 @@ class DMASample; * stable values. */ class AnalogInput : public ErrorBase, - public PIDSource, public Sendable, public SendableHelper { friend class AnalogTrigger; @@ -280,13 +278,6 @@ class AnalogInput : public ErrorBase, */ static double GetSampleRate(); - /** - * Get the Average value for the PID Source base object. - * - * @return The average voltage. - */ - double PIDGet() override; - /** * Indicates this input is used by a simulated device. * diff --git a/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h b/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h index f34e34f385..1f26242158 100644 --- a/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h +++ b/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h @@ -107,13 +107,6 @@ class AnalogPotentiometer : public ErrorBase, */ double Get() const override; - /** - * Implement the PIDSource interface. - * - * @return The current reading. - */ - double PIDGet() override; - void InitSendable(SendableBuilder& builder) override; private: diff --git a/wpilibc/src/main/native/include/frc/Encoder.h b/wpilibc/src/main/native/include/frc/Encoder.h index 973e995434..db96187d6a 100644 --- a/wpilibc/src/main/native/include/frc/Encoder.h +++ b/wpilibc/src/main/native/include/frc/Encoder.h @@ -11,7 +11,6 @@ #include "frc/Counter.h" #include "frc/CounterBase.h" #include "frc/ErrorBase.h" -#include "frc/PIDSource.h" #include "frc/smartdashboard/Sendable.h" #include "frc/smartdashboard/SendableHelper.h" @@ -40,7 +39,6 @@ class DMASample; */ class Encoder : public ErrorBase, public CounterBase, - public PIDSource, public Sendable, public SendableHelper { friend class DMA; @@ -314,8 +312,6 @@ class Encoder : public ErrorBase, */ int GetSamplesToAverage() const; - double PIDGet() override; - /** * Set the index source for the encoder. * diff --git a/wpilibc/src/main/native/include/frc/GyroBase.h b/wpilibc/src/main/native/include/frc/GyroBase.h index cec8a6f4a8..004d146874 100644 --- a/wpilibc/src/main/native/include/frc/GyroBase.h +++ b/wpilibc/src/main/native/include/frc/GyroBase.h @@ -5,7 +5,6 @@ #pragma once #include "frc/ErrorBase.h" -#include "frc/PIDSource.h" #include "frc/interfaces/Gyro.h" #include "frc/smartdashboard/Sendable.h" #include "frc/smartdashboard/SendableHelper.h" @@ -18,7 +17,6 @@ namespace frc { */ class GyroBase : public Gyro, public ErrorBase, - public PIDSource, public Sendable, public SendableHelper { public: @@ -26,15 +24,6 @@ class GyroBase : public Gyro, GyroBase(GyroBase&&) = default; GyroBase& operator=(GyroBase&&) = default; - // PIDSource interface - /** - * Get the PIDOutput for the PIDSource base object. Can be set to return - * angle or rate using SetPIDSourceType(). Defaults to angle. - * - * @return The PIDOutput (angle or rate, defaults to angle) - */ - double PIDGet() override; - void InitSendable(SendableBuilder& builder) override; }; diff --git a/wpilibc/src/main/native/include/frc/NidecBrushless.h b/wpilibc/src/main/native/include/frc/NidecBrushless.h index 3f12d6235d..5e1becaae6 100644 --- a/wpilibc/src/main/native/include/frc/NidecBrushless.h +++ b/wpilibc/src/main/native/include/frc/NidecBrushless.h @@ -73,14 +73,6 @@ class NidecBrushless : public SpeedController, */ void Enable(); - // PIDOutput interface - /** - * Write out the PID value as seen in the PIDOutput base object. - * - * @param output Write out the PWM value as was found in the PIDController - */ - void PIDWrite(double output) override; - // MotorSafety interface void StopMotor() override; void GetDescription(wpi::raw_ostream& desc) const override; diff --git a/wpilibc/src/main/native/include/frc/PWMSpeedController.h b/wpilibc/src/main/native/include/frc/PWMSpeedController.h index 9d6f65af3c..786855e756 100644 --- a/wpilibc/src/main/native/include/frc/PWMSpeedController.h +++ b/wpilibc/src/main/native/include/frc/PWMSpeedController.h @@ -60,13 +60,6 @@ class PWMSpeedController : public SpeedController, int GetChannel() const; - /** - * Write out the PID value as seen in the PIDOutput base object. - * - * @param output Write out the PWM value as was found in the PIDController - */ - void PIDWrite(double output) override; - protected: /** * Constructor for a PWM Speed Controller connected via PWM. diff --git a/wpilibc/src/main/native/include/frc/SpeedController.h b/wpilibc/src/main/native/include/frc/SpeedController.h index 23e0d7b0ab..fcb5de9b68 100644 --- a/wpilibc/src/main/native/include/frc/SpeedController.h +++ b/wpilibc/src/main/native/include/frc/SpeedController.h @@ -6,14 +6,12 @@ #include -#include "frc/PIDOutput.h" - namespace frc { /** * Interface for speed controlling devices. */ -class SpeedController : public PIDOutput { +class SpeedController { public: virtual ~SpeedController() = default; diff --git a/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h b/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h index f7153c64fe..2b621109b4 100644 --- a/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h +++ b/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h @@ -32,7 +32,6 @@ class SpeedControllerGroup : public Sendable, bool GetInverted() const override; void Disable() override; void StopMotor() override; - void PIDWrite(double output) override; void InitSendable(SendableBuilder& builder) override; diff --git a/wpilibc/src/main/native/include/frc/Ultrasonic.h b/wpilibc/src/main/native/include/frc/Ultrasonic.h index 71afd73659..78afc97be5 100644 --- a/wpilibc/src/main/native/include/frc/Ultrasonic.h +++ b/wpilibc/src/main/native/include/frc/Ultrasonic.h @@ -13,7 +13,6 @@ #include "frc/Counter.h" #include "frc/ErrorBase.h" -#include "frc/PIDSource.h" #include "frc/smartdashboard/Sendable.h" #include "frc/smartdashboard/SendableHelper.h" @@ -36,11 +35,8 @@ class DigitalOutput; */ class Ultrasonic : public ErrorBase, public Sendable, - public PIDSource, public SendableHelper { public: - enum DistanceUnit { kInches = 0, kMilliMeters = 1 }; - /** * Create an instance of the Ultrasonic Sensor. * @@ -51,9 +47,8 @@ class Ultrasonic : public ErrorBase, * @param echoChannel The digital input channel that receives the echo. The * length of time that the echo is high represents the * round trip time of the ping, and the distance. - * @param units The units returned in either kInches or kMilliMeters */ - Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units = kInches); + Ultrasonic(int pingChannel, int echoChannel); /** * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo @@ -63,10 +58,8 @@ class Ultrasonic : public ErrorBase, * ping. Requires a 10uS pulse to start. * @param echoChannel The digital input object that times the return pulse to * determine the range. - * @param units The units returned in either kInches or kMilliMeters */ - Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel, - DistanceUnit units = kInches); + Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel); /** * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo @@ -76,10 +69,8 @@ class Ultrasonic : public ErrorBase, * ping. Requires a 10uS pulse to start. * @param echoChannel The digital input object that times the return pulse to * determine the range. - * @param units The units returned in either kInches or kMilliMeters */ - Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel, - DistanceUnit units = kInches); + Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel); /** * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo @@ -89,11 +80,9 @@ class Ultrasonic : public ErrorBase, * ping. Requires a 10uS pulse to start. * @param echoChannel The digital input object that times the return pulse to * determine the range. - * @param units The units returned in either kInches or kMilliMeters */ Ultrasonic(std::shared_ptr pingChannel, - std::shared_ptr echoChannel, - DistanceUnit units = kInches); + std::shared_ptr echoChannel); ~Ultrasonic() override; @@ -156,30 +145,6 @@ class Ultrasonic : public ErrorBase, void SetEnabled(bool enable); - /** - * Set the current DistanceUnit that should be used for the PIDSource base - * object. - * - * @param units The DistanceUnit that should be used. - */ - void SetDistanceUnits(DistanceUnit units); - - /** - * Get the current DistanceUnit that is used for the PIDSource base object. - * - * @return The type of DistanceUnit that is being used. - */ - DistanceUnit GetDistanceUnits() const; - - /** - * Get the range in the current DistanceUnit for the PIDSource base object. - * - * @return The range in DistanceUnit - */ - double PIDGet() override; - - void SetPIDSourceType(PIDSourceType pidSource) override; - void InitSendable(SendableBuilder& builder) override; private: @@ -228,7 +193,6 @@ class Ultrasonic : public ErrorBase, std::shared_ptr m_echoChannel; bool m_enabled = false; Counter m_counter; - DistanceUnit m_units; hal::SimDevice m_simDevice; hal::SimBoolean m_simRangeValid; diff --git a/wpilibc/src/main/native/include/frc/controller/PIDController.h b/wpilibc/src/main/native/include/frc/controller/PIDController.h index ba6aa4080b..29d9ad4f06 100644 --- a/wpilibc/src/main/native/include/frc/controller/PIDController.h +++ b/wpilibc/src/main/native/include/frc/controller/PIDController.h @@ -239,3 +239,9 @@ class PIDController : public frc::Sendable, }; } // namespace frc2 + +namespace frc { + +using frc2::PIDController; + +} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/filters/Filter.h b/wpilibc/src/main/native/include/frc/filters/Filter.h deleted file mode 100644 index 9ec3efb3dd..0000000000 --- a/wpilibc/src/main/native/include/frc/filters/Filter.h +++ /dev/null @@ -1,61 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include - -#include - -#include "frc/PIDSource.h" - -namespace frc { - -/** - * Interface for filters - * - * @deprecated only used by the deprecated LinearDigitalFilter - */ -class Filter : public PIDSource { - public: - WPI_DEPRECATED("This class is no longer used.") - explicit Filter(PIDSource& source); - WPI_DEPRECATED("This class is no longer used.") - explicit Filter(std::shared_ptr source); - ~Filter() override = default; - - Filter(Filter&&) = default; - Filter& operator=(Filter&&) = default; - - // PIDSource interface - void SetPIDSourceType(PIDSourceType pidSource) override; - PIDSourceType GetPIDSourceType() const override; - double PIDGet() override = 0; - - /** - * Returns the current filter estimate without also inserting new data as - * PIDGet() would do. - * - * @return The current filter estimate - */ - virtual double Get() const = 0; - - /** - * Reset the filter state - */ - virtual void Reset() = 0; - - protected: - /** - * Calls PIDGet() of source - * - * @return Current value of source - */ - double PIDGetSource(); - - private: - std::shared_ptr m_source; -}; - -} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/filters/LinearDigitalFilter.h b/wpilibc/src/main/native/include/frc/filters/LinearDigitalFilter.h deleted file mode 100644 index e26a79bc23..0000000000 --- a/wpilibc/src/main/native/include/frc/filters/LinearDigitalFilter.h +++ /dev/null @@ -1,223 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include -#include -#include - -#include -#include -#include - -#include "frc/filters/Filter.h" - -namespace frc { - -/** - * This class implements a linear, digital filter. All types of FIR and IIR - * filters are supported. Static factory methods are provided to create commonly - * used types of filters. - * - * Filters are of the form:
- * y[n] = (b0 * x[n] + b1 * x[n-1] + ... + bP * x[n-P]) - - * (a0 * y[n-1] + a2 * y[n-2] + ... + aQ * y[n-Q]) - * - * Where:
- * y[n] is the output at time "n"
- * x[n] is the input at time "n"
- * y[n-1] is the output from the LAST time step ("n-1")
- * x[n-1] is the input from the LAST time step ("n-1")
- * b0...bP are the "feedforward" (FIR) gains
- * a0...aQ are the "feedback" (IIR) gains
- * IMPORTANT! Note the "-" sign in front of the feedback term! This is a common - * convention in signal processing. - * - * What can linear filters do? Basically, they can filter, or diminish, the - * effects of undesirable input frequencies. High frequencies, or rapid changes, - * can be indicative of sensor noise or be otherwise undesirable. A "low pass" - * filter smooths out the signal, reducing the impact of these high frequency - * components. Likewise, a "high pass" filter gets rid of slow-moving signal - * components, letting you detect large changes more easily. - * - * Example FRC applications of filters: - * - Getting rid of noise from an analog sensor input (note: the roboRIO's FPGA - * can do this faster in hardware) - * - Smoothing out joystick input to prevent the wheels from slipping or the - * robot from tipping - * - Smoothing motor commands so that unnecessary strain isn't put on - * electrical or mechanical components - * - If you use clever gains, you can make a PID controller out of this class! - * - * For more on filters, I highly recommend the following articles:
- * http://en.wikipedia.org/wiki/Linear_filter
- * http://en.wikipedia.org/wiki/Iir_filter
- * http://en.wikipedia.org/wiki/Fir_filter
- * - * Note 1: PIDGet() should be called by the user on a known, regular period. - * You can set up a Notifier to do this (look at the WPILib PIDController - * class), or do it "inline" with code in a periodic function. - * - * Note 2: For ALL filters, gains are necessarily a function of frequency. If - * you make a filter that works well for you at, say, 100Hz, you will most - * definitely need to adjust the gains if you then want to run it at 200Hz! - * Combining this with Note 1 - the impetus is on YOU as a developer to make - * sure PIDGet() gets called at the desired, constant frequency! - * - * @deprecated Use LinearFilter class instead - */ -class LinearDigitalFilter : public Filter { - public: - /** - * Create a linear FIR or IIR filter. - * - * @param source The PIDSource object that is used to get values - * @param ffGains The "feed forward" or FIR gains - * @param fbGains The "feed back" or IIR gains - */ - WPI_DEPRECATED("Use LinearFilter class instead.") - LinearDigitalFilter(PIDSource& source, wpi::ArrayRef ffGains, - wpi::ArrayRef fbGains); - - /** - * Create a linear FIR or IIR filter. - * - * @param source The PIDSource object that is used to get values - * @param ffGains The "feed forward" or FIR gains - * @param fbGains The "feed back" or IIR gains - */ - WPI_DEPRECATED("Use LinearFilter class instead.") - LinearDigitalFilter(PIDSource& source, std::initializer_list ffGains, - std::initializer_list fbGains); - - /** - * Create a linear FIR or IIR filter. - * - * @param source The PIDSource object that is used to get values - * @param ffGains The "feed forward" or FIR gains - * @param fbGains The "feed back" or IIR gains - */ - WPI_DEPRECATED("Use LinearFilter class instead.") - LinearDigitalFilter(std::shared_ptr source, - wpi::ArrayRef ffGains, - wpi::ArrayRef fbGains); - - /** - * Create a linear FIR or IIR filter. - * - * @param source The PIDSource object that is used to get values - * @param ffGains The "feed forward" or FIR gains - * @param fbGains The "feed back" or IIR gains - */ - WPI_DEPRECATED("Use LinearFilter class instead.") - LinearDigitalFilter(std::shared_ptr source, - std::initializer_list ffGains, - std::initializer_list fbGains); - - LinearDigitalFilter(LinearDigitalFilter&&) = default; - LinearDigitalFilter& operator=(LinearDigitalFilter&&) = default; - - // Static methods to create commonly used filters - /** - * Creates a one-pole IIR low-pass filter of the form:
- * y[n] = (1 - gain) * x[n] + gain * y[n-1]
- * where gain = e-dt / T, T is the time constant in seconds - * - * This filter is stable for time constants greater than zero. - * - * @param source The PIDSource object that is used to get values - * @param timeConstant The discrete-time time constant in seconds - * @param period The period in seconds between samples taken by the user - */ - static LinearDigitalFilter SinglePoleIIR(PIDSource& source, - double timeConstant, double period); - - /** - * Creates a first-order high-pass filter of the form:
- * y[n] = gain * x[n] + (-gain) * x[n-1] + gain * y[n-1]
- * where gain = e-dt / T, T is the time constant in seconds - * - * This filter is stable for time constants greater than zero. - * - * @param source The PIDSource object that is used to get values - * @param timeConstant The discrete-time time constant in seconds - * @param period The period in seconds between samples taken by the user - */ - static LinearDigitalFilter HighPass(PIDSource& source, double timeConstant, - double period); - - /** - * Creates a K-tap FIR moving average filter of the form:
- * y[n] = 1/k * (x[k] + x[k-1] + … + x[0]) - * - * This filter is always stable. - * - * @param source The PIDSource object that is used to get values - * @param taps The number of samples to average over. Higher = smoother but - * slower - */ - static LinearDigitalFilter MovingAverage(PIDSource& source, int taps); - - /** - * Creates a one-pole IIR low-pass filter of the form:
- * y[n] = (1 - gain) * x[n] + gain * y[n-1]
- * where gain = e-dt / T, T is the time constant in seconds - * - * This filter is stable for time constants greater than zero. - * - * @param source The PIDSource object that is used to get values - * @param timeConstant The discrete-time time constant in seconds - * @param period The period in seconds between samples taken by the user - */ - static LinearDigitalFilter SinglePoleIIR(std::shared_ptr source, - double timeConstant, double period); - - /** - * Creates a first-order high-pass filter of the form:
- * y[n] = gain * x[n] + (-gain) * x[n-1] + gain * y[n-1]
- * where gain = e-dt / T, T is the time constant in seconds - * - * This filter is stable for time constants greater than zero. - * - * @param source The PIDSource object that is used to get values - * @param timeConstant The discrete-time time constant in seconds - * @param period The period in seconds between samples taken by the user - */ - static LinearDigitalFilter HighPass(std::shared_ptr source, - double timeConstant, double period); - - /** - * Creates a K-tap FIR moving average filter of the form:
- * y[n] = 1/k * (x[k] + x[k-1] + … + x[0]) - * - * This filter is always stable. - * - * @param source The PIDSource object that is used to get values - * @param taps The number of samples to average over. Higher = smoother but - * slower - */ - static LinearDigitalFilter MovingAverage(std::shared_ptr source, - int taps); - - // Filter interface - double Get() const override; - void Reset() override; - - // PIDSource interface - /** - * Calculates the next value of the filter - * - * @return The filtered value at this step - */ - double PIDGet() override; - - private: - wpi::circular_buffer m_inputs; - wpi::circular_buffer m_outputs; - std::vector m_inputGains; - std::vector m_outputGains; -}; - -} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/interfaces/Potentiometer.h b/wpilibc/src/main/native/include/frc/interfaces/Potentiometer.h index f3392c9b03..ac3125c9f5 100644 --- a/wpilibc/src/main/native/include/frc/interfaces/Potentiometer.h +++ b/wpilibc/src/main/native/include/frc/interfaces/Potentiometer.h @@ -4,17 +4,15 @@ #pragma once -#include "frc/PIDSource.h" - namespace frc { /** * Interface for potentiometers. */ -class Potentiometer : public PIDSource { +class Potentiometer { public: Potentiometer() = default; - ~Potentiometer() override = default; + virtual ~Potentiometer() = default; Potentiometer(Potentiometer&&) = default; Potentiometer& operator=(Potentiometer&&) = default; @@ -25,8 +23,6 @@ class Potentiometer : public PIDSource { * @return The current set speed. Value is between -1.0 and 1.0. */ virtual double Get() const = 0; - - void SetPIDSourceType(PIDSourceType pidSource) override; }; } // namespace frc diff --git a/wpilibc/src/test/native/cpp/MockSpeedController.cpp b/wpilibc/src/test/native/cpp/MockSpeedController.cpp index f4d3459f8b..31ccb075fd 100644 --- a/wpilibc/src/test/native/cpp/MockSpeedController.cpp +++ b/wpilibc/src/test/native/cpp/MockSpeedController.cpp @@ -29,7 +29,3 @@ void MockSpeedController::Disable() { void MockSpeedController::StopMotor() { Disable(); } - -void MockSpeedController::PIDWrite(double output) { - Set(output); -} diff --git a/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp b/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp index 597d228644..0f62530db5 100644 --- a/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp +++ b/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp @@ -121,13 +121,5 @@ TEST_P(SpeedControllerGroupTest, StopMotor) { } } -TEST_P(SpeedControllerGroupTest, PIDWrite) { - m_group->PIDWrite(1.0); - - for (auto& speedController : m_speedControllers) { - EXPECT_FLOAT_EQ(speedController.Get(), 1.0); - } -} - INSTANTIATE_TEST_SUITE_P(Test, SpeedControllerGroupTest, testing::Values(TEST_ONE, TEST_TWO, TEST_THREE)); diff --git a/wpilibc/src/test/native/include/MockSpeedController.h b/wpilibc/src/test/native/include/MockSpeedController.h index ff0cea8e58..a5e119bae9 100644 --- a/wpilibc/src/test/native/include/MockSpeedController.h +++ b/wpilibc/src/test/native/include/MockSpeedController.h @@ -17,8 +17,6 @@ class MockSpeedController : public SpeedController { void Disable() override; void StopMotor() override; - void PIDWrite(double output) override; - private: double m_speed = 0.0; bool m_isInverted = false; diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h index cb2c748550..9d7e5e54e8 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h @@ -79,6 +79,4 @@ class ExampleSmartMotorController : public frc::SpeedController { void Disable() override {} void StopMotor() override {} - - void PIDWrite(double output) override {} }; diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h index 46720e1f81..5e5b1d53cd 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h @@ -80,8 +80,6 @@ class ExampleSmartMotorController : public frc::SpeedController { void StopMotor() override {} - void PIDWrite(double output) override {} - private: double m_value = 0.0; }; diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h index cb2c748550..9d7e5e54e8 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h @@ -79,6 +79,4 @@ class ExampleSmartMotorController : public frc::SpeedController { void Disable() override {} void StopMotor() override {} - - void PIDWrite(double output) override {} }; diff --git a/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/DriveTrain.cpp b/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/DriveTrain.cpp index e39972384d..e9c878a3e6 100644 --- a/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/DriveTrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/DriveTrain.cpp @@ -24,10 +24,6 @@ DriveTrain::DriveTrain() : frc::Subsystem("DriveTrain") { m_leftCIMs.SetInverted(true); m_rightCIMs.SetInverted(true); - // Configure encoders - m_rightEncoder.SetPIDSourceType(frc::PIDSourceType::kDisplacement); - m_leftEncoder.SetPIDSourceType(frc::PIDSourceType::kDisplacement); - #ifndef SIMULATION // Converts to feet m_rightEncoder.SetDistancePerPulse(0.0785398); diff --git a/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Pivot.cpp b/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Pivot.cpp index c8cf025619..ba6f1a6d01 100644 --- a/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Pivot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Pivot.cpp @@ -27,7 +27,7 @@ double Pivot::ReturnPIDInput() { } void Pivot::UsePIDOutput(double output) { - m_motor.PIDWrite(output); + m_motor.Set(output); } bool Pivot::IsAtUpperLimit() { 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 960518cb63..b0395b859a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java @@ -16,12 +16,11 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; * 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 implements PIDSource, Sendable, AutoCloseable { +public class AnalogAccelerometer implements Sendable, AutoCloseable { private AnalogInput m_analogChannel; private double m_voltsPerG = 1.0; private double m_zeroGVoltage = 2.5; private final boolean m_allocatedChannel; - protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement; /** Common initialization. */ private void initAccelerometer() { @@ -108,26 +107,6 @@ public class AnalogAccelerometer implements PIDSource, Sendable, AutoCloseable { m_zeroGVoltage = zero; } - @Override - public void setPIDSourceType(PIDSourceType pidSource) { - m_pidSource = pidSource; - } - - @Override - public PIDSourceType getPIDSourceType() { - return m_pidSource; - } - - /** - * Get the Acceleration for the PID Source parent. - * - * @return The current acceleration in Gs. - */ - @Override - public double pidGet() { - return getAcceleration(); - } - @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Accelerometer"); 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 ccec9604c0..428801ead6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java @@ -25,13 +25,12 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; * 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 implements PIDSource, Sendable, AutoCloseable { +public class AnalogInput implements Sendable, AutoCloseable { private static final int kAccumulatorSlot = 1; int m_port; // explicit no modifier, private and package accessible. private int m_channel; private static final int[] kAccumulatorChannels = {0, 1}; private long m_accumulatorOffset; - protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement; /** * Construct an analog channel. @@ -322,26 +321,6 @@ public class AnalogInput implements PIDSource, Sendable, AutoCloseable { return AnalogJNI.getAnalogSampleRate(); } - @Override - public void setPIDSourceType(PIDSourceType pidSource) { - m_pidSource = pidSource; - } - - @Override - public PIDSourceType getPIDSourceType() { - return m_pidSource; - } - - /** - * Get the average voltage for use with PIDController. - * - * @return the average voltage - */ - @Override - public double pidGet() { - return getAverageVoltage(); - } - /** * Indicates this input is used by a simulated device. * 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 34ea6d1ac9..9c74f5e216 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java @@ -18,7 +18,6 @@ public class AnalogPotentiometer implements Potentiometer, Sendable, AutoCloseab private boolean m_initAnalogInput; private double m_fullRange; private double m_offset; - protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement; /** * AnalogPotentiometer constructor. @@ -129,29 +128,6 @@ public class AnalogPotentiometer implements Potentiometer, Sendable, AutoCloseab + m_offset; } - @Override - public void setPIDSourceType(PIDSourceType pidSource) { - if (!pidSource.equals(PIDSourceType.kDisplacement)) { - throw new IllegalArgumentException("Only displacement PID is allowed for potentiometers."); - } - m_pidSource = pidSource; - } - - @Override - public PIDSourceType getPIDSourceType() { - return m_pidSource; - } - - /** - * Implement the PIDSource interface. - * - * @return The current reading. - */ - @Override - public double pidGet() { - return get(); - } - @Override public void initSendable(SendableBuilder builder) { if (m_analogInput != null) { 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 7cc082192f..5ed499497a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java @@ -26,7 +26,7 @@ import java.nio.ByteOrder; *

All counters will immediately start counting - reset() them if you need them to be zeroed * before use. */ -public class Counter implements CounterBase, PIDSource, Sendable, AutoCloseable { +public class Counter implements CounterBase, Sendable, AutoCloseable { /** Mode determines how and what the counter counts. */ public enum Mode { /** mode: two pulse. */ @@ -51,7 +51,6 @@ public class Counter implements CounterBase, PIDSource, Sendable, AutoCloseable private boolean m_allocatedDownSource; private int m_counter; // /< The FPGA counter object. private int m_index; // /< The index of this counter. - private PIDSourceType m_pidSource; private double m_distancePerPulse; // distance of travel for each tick /** Create an instance of a counter with the given mode. */ @@ -507,39 +506,6 @@ public class Counter implements CounterBase, PIDSource, Sendable, AutoCloseable m_distancePerPulse = distancePerPulse; } - /** - * Set which parameter of the encoder you are using as a process control variable. The counter - * class supports the rate and distance parameters. - * - * @param pidSource An enum to select the parameter. - */ - @Override - public void setPIDSourceType(PIDSourceType pidSource) { - requireNonNullParam(pidSource, "pidSource", "setPIDSourceType"); - if (pidSource != PIDSourceType.kDisplacement && pidSource != PIDSourceType.kRate) { - throw new IllegalArgumentException("PID Source parameter was not valid type: " + pidSource); - } - - m_pidSource = pidSource; - } - - @Override - public PIDSourceType getPIDSourceType() { - return m_pidSource; - } - - @Override - public double pidGet() { - switch (m_pidSource) { - case kDisplacement: - return getDistance(); - case kRate: - return getRate(); - default: - return 0.0; - } - } - @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Counter"); 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 019eaa5d93..2c9a204590 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java @@ -27,7 +27,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; *

All encoders will immediately start counting - reset() them if you need them to be zeroed * before use. */ -public class Encoder implements CounterBase, PIDSource, Sendable, AutoCloseable { +public class Encoder implements CounterBase, Sendable, AutoCloseable { public enum IndexingType { kResetWhileHigh(0), kResetWhileLow(1), @@ -51,7 +51,6 @@ public class Encoder implements CounterBase, PIDSource, Sendable, AutoCloseable private boolean m_allocatedA; private boolean m_allocatedB; private boolean m_allocatedI; - private PIDSourceType m_pidSource; private int m_encoder; // the HAL encoder object @@ -73,8 +72,6 @@ public class Encoder implements CounterBase, PIDSource, Sendable, AutoCloseable reverseDirection, type.value); - m_pidSource = PIDSourceType.kDisplacement; - int fpgaIndex = getFPGAIndex(); HAL.report(tResourceType.kResourceType_Encoder, fpgaIndex + 1, type.value + 1); SendableRegistry.addLW(this, "Encoder", fpgaIndex); @@ -481,39 +478,6 @@ public class Encoder implements CounterBase, PIDSource, Sendable, AutoCloseable return EncoderJNI.getEncoderSamplesToAverage(m_encoder); } - /** - * Set which parameter of the encoder you are using as a process control variable. The encoder - * class supports the rate and distance parameters. - * - * @param pidSource An enum to select the parameter. - */ - @Override - public void setPIDSourceType(PIDSourceType pidSource) { - m_pidSource = pidSource; - } - - @Override - public PIDSourceType getPIDSourceType() { - return m_pidSource; - } - - /** - * Implement the PIDSource interface. - * - * @return The current value of the selected source parameter. - */ - @Override - public double pidGet() { - switch (m_pidSource) { - case kDisplacement: - return getDistance(); - case kRate: - return getRate(); - default: - return 0.0; - } - } - /** * Set the index source for the encoder. When this source is activated, the encoder count * automatically resets. 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 4b180d5c92..8bc1076541 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/GyroBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/GyroBase.java @@ -8,43 +8,7 @@ import edu.wpi.first.wpilibj.interfaces.Gyro; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; /** GyroBase is the common base class for Gyro implementations such as AnalogGyro. */ -public abstract class GyroBase implements Gyro, PIDSource, Sendable { - private PIDSourceType m_pidSource = PIDSourceType.kDisplacement; - - /** - * Set which parameter of the gyro you are using as a process control variable. The Gyro class - * supports the rate and displacement parameters - * - * @param pidSource An enum to select the parameter. - */ - @Override - public void setPIDSourceType(PIDSourceType pidSource) { - m_pidSource = pidSource; - } - - @Override - public PIDSourceType getPIDSourceType() { - return m_pidSource; - } - - /** - * Get the output of the gyro for use with PIDControllers. May be the angle or rate depending on - * the set PIDSourceType - * - * @return the output according to the gyro - */ - @Override - public double pidGet() { - switch (m_pidSource) { - case kRate: - return getRate(); - case kDisplacement: - return getAngle(); - default: - return 0.0; - } - } - +public abstract class GyroBase implements Gyro, Sendable { @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Gyro"); 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 c051d314b7..6a9d9e8b2d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java @@ -89,16 +89,6 @@ public class NidecBrushless extends MotorSafety return m_isInverted; } - /** - * Write out the PID value as seen in the PIDOutput base object. - * - * @param output Write out the PWM value as was found in the PIDController - */ - @Override - public void pidWrite(double output) { - set(output); - } - /** * Stop the motor. This is called by the MotorSafety object when it has a timeout for this PWM and * needs to stop it from running. Calling set() will re-enable the motor. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java index 2db8baf5fe..4a0f7e60f1 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java @@ -92,16 +92,6 @@ public abstract class PWMSpeedController extends MotorSafety return m_pwm.getChannel(); } - /** - * Write out the PID value as seen in the PIDOutput base object. - * - * @param output Write out the PWM value as was found in the PIDController - */ - @Override - public void pidWrite(double output) { - set(output); - } - @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Speed Controller"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedController.java index f795ca77a0..7d03f477a0 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedController.java @@ -5,8 +5,7 @@ package edu.wpi.first.wpilibj; /** Interface for speed controlling devices. */ -@SuppressWarnings("removal") -public interface SpeedController extends PIDOutput { +public interface SpeedController { /** * Common interface for setting the speed of a speed controller. * 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 f8a9fb2c5e..e0a95c3079 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java @@ -87,11 +87,6 @@ public class SpeedControllerGroup implements SpeedController, Sendable, AutoClos } } - @Override - public void pidWrite(double output) { - set(output); - } - @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Speed Controller"); 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 81c1bcf534..346ddb9738 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java @@ -26,15 +26,7 @@ import java.util.List; * echo is received. The time that the line is high determines the round trip distance (time of * flight). */ -public class Ultrasonic implements PIDSource, Sendable, AutoCloseable { - /** The units to return when PIDGet is called. */ - public enum Unit { - /** Use inches for PIDGet. */ - kInches, - /** Use millimeters for PIDGet. */ - kMillimeters - } - +public class Ultrasonic implements Sendable, AutoCloseable { // Time (sec) for the ping trigger pulse. private static final double kPingTime = 10 * 1e-6; private static final double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0; @@ -44,14 +36,12 @@ public class Ultrasonic implements PIDSource, Sendable, AutoCloseable { private static volatile boolean m_automaticEnabled; private DigitalInput m_echoChannel; private DigitalOutput m_pingChannel; - private boolean m_allocatedChannels; + private final boolean m_allocatedChannels; private boolean m_enabled; private Counter m_counter; // task doing the round-robin automatic sensing private static Thread m_task; - private Unit m_units; private static int m_instances; - protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement; private SimDevice m_simDevice; private SimBoolean m_simRangeValid; @@ -128,31 +118,16 @@ public class Ultrasonic implements PIDSource, Sendable, AutoCloseable { * sending the ping. * @param echoChannel The digital input channel that receives the echo. The length of time that * the echo is high represents the round trip time of the ping, and the distance. - * @param units The units returned in either kInches or kMilliMeters */ - public Ultrasonic(final int pingChannel, final int echoChannel, Unit units) { + public Ultrasonic(final int pingChannel, final int echoChannel) { m_pingChannel = new DigitalOutput(pingChannel); m_echoChannel = new DigitalInput(echoChannel); SendableRegistry.addChild(this, m_pingChannel); SendableRegistry.addChild(this, m_echoChannel); m_allocatedChannels = true; - m_units = units; initialize(); } - /** - * Create an instance of the Ultrasonic Sensor. This is designed to supchannel the Daventech SRF04 - * and Vex ultrasonic sensors. Default unit is inches. - * - * @param pingChannel The digital output channel that sends the pulse to initiate the sensor - * sending the ping. - * @param echoChannel The digital input channel that receives the echo. The length of time that - * the echo is high represents the round trip time of the ping, and the distance. - */ - public Ultrasonic(final int pingChannel, final int echoChannel) { - this(pingChannel, echoChannel, Unit.kInches); - } - /** * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo channel and a * DigitalOutput for the ping channel. @@ -160,31 +135,17 @@ public class Ultrasonic implements PIDSource, Sendable, AutoCloseable { * @param pingChannel The digital output object that starts the sensor doing a ping. Requires a * 10uS pulse to start. * @param echoChannel The digital input object that times the return pulse to determine the range. - * @param units The units returned in either kInches or kMilliMeters */ - public Ultrasonic(DigitalOutput pingChannel, DigitalInput echoChannel, Unit units) { + public Ultrasonic(DigitalOutput pingChannel, DigitalInput echoChannel) { requireNonNull(pingChannel, "Provided ping channel was null"); requireNonNull(echoChannel, "Provided echo channel was null"); m_allocatedChannels = false; m_pingChannel = pingChannel; m_echoChannel = echoChannel; - m_units = units; initialize(); } - /** - * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo channel and a - * DigitalOutput for the ping channel. Default unit is inches. - * - * @param pingChannel The digital output object that starts the sensor doing a ping. Requires a - * 10uS pulse to start. - * @param echoChannel The digital input object that times the return pulse to determine the range. - */ - public Ultrasonic(DigitalOutput pingChannel, DigitalInput echoChannel) { - this(pingChannel, echoChannel, Unit.kInches); - } - /** * Destructor for the ultrasonic sensor. Delete the instance of the ultrasonic sensor by freeing * the allocated digital channels. If the system was in automatic mode (round robin), then it is @@ -326,54 +287,6 @@ public class Ultrasonic implements PIDSource, Sendable, AutoCloseable { return getRangeInches() * 25.4; } - @Override - public void setPIDSourceType(PIDSourceType pidSource) { - if (!pidSource.equals(PIDSourceType.kDisplacement)) { - throw new IllegalArgumentException("Only displacement PID is allowed for ultrasonics."); - } - m_pidSource = pidSource; - } - - @Override - public PIDSourceType getPIDSourceType() { - return m_pidSource; - } - - /** - * Get the range in the current DistanceUnit for the PIDSource base object. - * - * @return The range in DistanceUnit - */ - @Override - public double pidGet() { - switch (m_units) { - case kInches: - return getRangeInches(); - case kMillimeters: - return getRangeMM(); - default: - return 0.0; - } - } - - /** - * Set the current DistanceUnit that should be used for the PIDSource base object. - * - * @param units The DistanceUnit that should be used. - */ - public void setDistanceUnits(Unit units) { - m_units = units; - } - - /** - * Get the current DistanceUnit that is used for the PIDSource base object. - * - * @return The type of DistanceUnit that is being used. - */ - public Unit getDistanceUnits() { - return m_units; - } - /** * Is the ultrasonic enabled. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/Filter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/Filter.java deleted file mode 100644 index f80eb30896..0000000000 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/Filter.java +++ /dev/null @@ -1,54 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package edu.wpi.first.wpilibj.filters; - -import edu.wpi.first.wpilibj.PIDSource; -import edu.wpi.first.wpilibj.PIDSourceType; - -/** - * Superclass for filters. - * - * @deprecated This class is no longer used. - */ -@Deprecated(since = "2020", forRemoval = true) -public abstract class Filter implements PIDSource { - private final PIDSource m_source; - - public Filter(PIDSource source) { - m_source = source; - } - - @Override - public void setPIDSourceType(PIDSourceType pidSource) { - m_source.setPIDSourceType(pidSource); - } - - @Override - public PIDSourceType getPIDSourceType() { - return m_source.getPIDSourceType(); - } - - @Override - public abstract double pidGet(); - - /** - * Returns the current filter estimate without also inserting new data as pidGet() would do. - * - * @return The current filter estimate - */ - public abstract double get(); - - /** Reset the filter state. */ - public abstract void reset(); - - /** - * Calls PIDGet() of source. - * - * @return Current value of source - */ - protected double pidGetSource() { - return m_source.pidGet(); - } -} diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/LinearDigitalFilter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/LinearDigitalFilter.java deleted file mode 100644 index 4499f4b47f..0000000000 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/LinearDigitalFilter.java +++ /dev/null @@ -1,187 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package edu.wpi.first.wpilibj.filters; - -import edu.wpi.first.hal.FRCNetComm.tResourceType; -import edu.wpi.first.hal.HAL; -import edu.wpi.first.wpilibj.PIDSource; -import edu.wpi.first.wpiutil.CircularBuffer; -import java.util.Arrays; - -/** - * This class implements a linear, digital filter. All types of FIR and IIR filters are supported. - * Static factory methods are provided to create commonly used types of filters. - * - *

Filters are of the form: y[n] = (b0*x[n] + b1*x[n-1] + ... + bP*x[n-P]) - (a0*y[n-1] + - * a2*y[n-2] + ... + aQ*y[n-Q]) - * - *

Where: y[n] is the output at time "n" x[n] is the input at time "n" y[n-1] is the output from - * the LAST time step ("n-1") x[n-1] is the input from the LAST time step ("n-1") b0...bP are the - * "feedforward" (FIR) gains a0...aQ are the "feedback" (IIR) gains IMPORTANT! Note the "-" sign in - * front of the feedback term! This is a common convention in signal processing. - * - *

What can linear filters do? Basically, they can filter, or diminish, the effects of - * undesirable input frequencies. High frequencies, or rapid changes, can be indicative of sensor - * noise or be otherwise undesirable. A "low pass" filter smooths out the signal, reducing the - * impact of these high frequency components. Likewise, a "high pass" filter gets rid of slow-moving - * signal components, letting you detect large changes more easily. - * - *

Example FRC applications of filters: - Getting rid of noise from an analog sensor input (note: - * the roboRIO's FPGA can do this faster in hardware) - Smoothing out joystick input to prevent the - * wheels from slipping or the robot from tipping - Smoothing motor commands so that unnecessary - * strain isn't put on electrical or mechanical components - If you use clever gains, you can make a - * PID controller out of this class! - * - *

For more on filters, I highly recommend the following articles: http://en.wikipedia - * .org/wiki/Linear_filter http://en.wikipedia.org/wiki/Iir_filter http://en.wikipedia - * .org/wiki/Fir_filter - * - *

Note 1: PIDGet() should be called by the user on a known, regular period. You can set up a - * Notifier to do this (look at the WPILib PIDController class), or do it "inline" with code in a - * periodic function. - * - *

Note 2: For ALL filters, gains are necessarily a function of frequency. If you make a filter - * that works well for you at, say, 100Hz, you will most definitely need to adjust the gains if you - * then want to run it at 200Hz! Combining this with Note 1 - the impetus is on YOU as a developer - * to make sure PIDGet() gets called at the desired, constant frequency! - * - * @deprecated Use LinearFilter class instead. - */ -@Deprecated -public class LinearDigitalFilter extends Filter { - private static int instances; - - private final CircularBuffer m_inputs; - private final CircularBuffer m_outputs; - private final double[] m_inputGains; - private final double[] m_outputGains; - - /** - * Create a linear FIR or IIR filter. - * - * @param source The PIDSource object that is used to get values - * @param ffGains The "feed forward" or FIR gains - * @param fbGains The "feed back" or IIR gains - */ - public LinearDigitalFilter(PIDSource source, double[] ffGains, double[] fbGains) { - super(source); - m_inputs = new CircularBuffer(ffGains.length); - m_outputs = new CircularBuffer(fbGains.length); - m_inputGains = Arrays.copyOf(ffGains, ffGains.length); - m_outputGains = Arrays.copyOf(fbGains, fbGains.length); - - instances++; - HAL.report(tResourceType.kResourceType_LinearFilter, instances); - } - - /** - * Creates a one-pole IIR low-pass filter of the form: y[n] = (1-gain)*x[n] + gain*y[n-1] where - * gain = e^(-dt / T), T is the time constant in seconds. - * - *

This filter is stable for time constants greater than zero. - * - * @param source The PIDSource object that is used to get values - * @param timeConstant The discrete-time time constant in seconds - * @param period The period in seconds between samples taken by the user - */ - public static LinearDigitalFilter singlePoleIIR( - PIDSource source, double timeConstant, double period) { - double gain = Math.exp(-period / timeConstant); - double[] ffGains = {1.0 - gain}; - double[] fbGains = {-gain}; - - return new LinearDigitalFilter(source, ffGains, fbGains); - } - - /** - * Creates a first-order high-pass filter of the form: y[n] = gain*x[n] + (-gain)*x[n-1] + - * gain*y[n-1] where gain = e^(-dt / T), T is the time constant in seconds. - * - *

This filter is stable for time constants greater than zero. - * - * @param source The PIDSource object that is used to get values - * @param timeConstant The discrete-time time constant in seconds - * @param period The period in seconds between samples taken by the user - */ - public static LinearDigitalFilter highPass(PIDSource source, double timeConstant, double period) { - double gain = Math.exp(-period / timeConstant); - double[] ffGains = {gain, -gain}; - double[] fbGains = {-gain}; - - return new LinearDigitalFilter(source, ffGains, fbGains); - } - - /** - * Creates a K-tap FIR moving average filter of the form: y[n] = 1/k * (x[k] + x[k-1] + ... + - * x[0]). - * - *

This filter is always stable. - * - * @param source The PIDSource object that is used to get values - * @param taps The number of samples to average over. Higher = smoother but slower - * @throws IllegalArgumentException if number of taps is less than 1 - */ - public static LinearDigitalFilter movingAverage(PIDSource source, int taps) { - if (taps <= 0) { - throw new IllegalArgumentException("Number of taps was not at least 1"); - } - - double[] ffGains = new double[taps]; - for (int i = 0; i < ffGains.length; i++) { - ffGains[i] = 1.0 / taps; - } - - double[] fbGains = new double[0]; - - return new LinearDigitalFilter(source, ffGains, fbGains); - } - - @Override - public double get() { - double retVal = 0.0; - - // Calculate the new value - for (int i = 0; i < m_inputGains.length; i++) { - retVal += m_inputs.get(i) * m_inputGains[i]; - } - for (int i = 0; i < m_outputGains.length; i++) { - retVal -= m_outputs.get(i) * m_outputGains[i]; - } - - return retVal; - } - - @Override - public void reset() { - m_inputs.clear(); - m_outputs.clear(); - } - - /** - * Calculates the next value of the filter. - * - * @return The filtered value at this step - */ - @Override - public double pidGet() { - double retVal = 0.0; - - // Rotate the inputs - m_inputs.addFirst(pidGetSource()); - - // Calculate the new value - for (int i = 0; i < m_inputGains.length; i++) { - retVal += m_inputs.get(i) * m_inputGains[i]; - } - for (int i = 0; i < m_outputGains.length; i++) { - retVal -= m_outputs.get(i) * m_outputGains[i]; - } - - // Rotate the outputs - m_outputs.addFirst(retVal); - - return retVal; - } -} diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Potentiometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Potentiometer.java index e0178273b0..99735c379f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Potentiometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Potentiometer.java @@ -4,9 +4,7 @@ package edu.wpi.first.wpilibj.interfaces; -import edu.wpi.first.wpilibj.PIDSource; - /** Interface for a Potentiometer. */ -public interface Potentiometer extends PIDSource { +public interface Potentiometer { double get(); } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/MockSpeedController.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/MockSpeedController.java index 4d55b9fef8..a7bd4a802f 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/MockSpeedController.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/MockSpeedController.java @@ -37,9 +37,4 @@ public class MockSpeedController implements SpeedController { public void stopMotor() { disable(); } - - @Override - public void pidWrite(double output) { - set(output); - } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SpeedControllerGroupTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SpeedControllerGroupTest.java index c421471a9c..5f4a80cbff 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SpeedControllerGroupTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SpeedControllerGroupTest.java @@ -98,15 +98,4 @@ class SpeedControllerGroupTest { Arrays.stream(speedControllers).mapToDouble(SpeedController::get).toArray(), 0.00005); } - - @ParameterizedTest - @MethodSource("speedControllerArguments") - void pidWriteTest(final SpeedControllerGroup group, final SpeedController[] speedControllers) { - group.pidWrite(1.0); - - assertArrayEquals( - DoubleStream.generate(() -> 1.0).limit(speedControllers.length).toArray(), - Arrays.stream(speedControllers).mapToDouble(SpeedController::get).toArray(), - 0.00005); - } } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/ExampleSmartMotorController.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/ExampleSmartMotorController.java index fa31d457fe..fb2329c007 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/ExampleSmartMotorController.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/ExampleSmartMotorController.java @@ -93,7 +93,4 @@ public class ExampleSmartMotorController implements SpeedController { @Override public void stopMotor() {} - - @Override - public void pidWrite(double output) {} } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/ExampleSmartMotorController.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/ExampleSmartMotorController.java index bacac9e4be..615ed18bcd 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/ExampleSmartMotorController.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/ExampleSmartMotorController.java @@ -97,7 +97,4 @@ public class ExampleSmartMotorController implements SpeedController { @Override public void stopMotor() {} - - @Override - public void pidWrite(double output) {} } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java index 1577770e6b..d2ea6eea42 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java @@ -93,7 +93,4 @@ public class ExampleSmartMotorController implements SpeedController { @Override public void stopMotor() {} - - @Override - public void pidWrite(double output) {} } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Pivot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Pivot.java index 916ef56a1f..184125002f 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Pivot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Pivot.java @@ -65,7 +65,7 @@ public class Pivot extends PIDSubsystem { /** Set the motor speed based off of the PID output. */ @Override protected void usePIDOutput(double output) { - m_motor.pidWrite(output); + m_motor.set(output); } /** If the pivot is at its upper limit. */ diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockSpeedController.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockSpeedController.java index 4d55b9fef8..a7bd4a802f 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockSpeedController.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockSpeedController.java @@ -37,9 +37,4 @@ public class MockSpeedController implements SpeedController { public void stopMotor() { disable(); } - - @Override - public void pidWrite(double output) { - set(output); - } }