Remove most 2022 deprecations (#4205)

Excludes "old" commands and SimDevice functions.
This commit is contained in:
Tyler Veness
2022-05-04 20:37:27 -07:00
committed by GitHub
parent ce1a7d698a
commit ee03a7ad3b
75 changed files with 165 additions and 1882 deletions

View File

@@ -37,27 +37,9 @@ import java.util.concurrent.atomic.AtomicInteger;
public final class CameraServer {
public static final int kBasePort = 1181;
@Deprecated public static final int kSize640x480 = 0;
@Deprecated public static final int kSize320x240 = 1;
@Deprecated public static final int kSize160x120 = 2;
private static final String kPublishName = "/CameraPublisher";
private static CameraServer server;
/**
* Get the CameraServer instance.
*
* @return The CameraServer instance.
* @deprecated Use the static methods
*/
@Deprecated
public static synchronized CameraServer getInstance() {
if (server == null) {
server = new CameraServer();
}
return server;
}
private static final AtomicInteger m_defaultUsbDevice = new AtomicInteger();
private static String m_primarySourceName;
private static final Map<String, VideoSource> m_sources = new HashMap<>();

View File

@@ -52,12 +52,6 @@ static Instance& GetInstance() {
return instance;
}
CameraServer* CameraServer::GetInstance() {
::GetInstance();
static CameraServer instance;
return &instance;
}
static std::string_view MakeSourceValue(CS_Source source,
wpi::SmallVectorImpl<char>& buf) {
CS_Status status = 0;

View File

@@ -9,7 +9,6 @@
#include <string>
#include <string_view>
#include <wpi/deprecated.h>
#include <wpi/span.h>
#include "cscore.h"
@@ -29,13 +28,6 @@ class CameraServer {
static constexpr int kSize320x240 = 1;
static constexpr int kSize160x120 = 2;
/**
* Get the CameraServer instance.
* @deprecated Use the static methods
*/
WPI_DEPRECATED("Use static methods")
static CameraServer* GetInstance();
/**
* Start automatically capturing images to send to the dashboard.
*

View File

@@ -12,6 +12,7 @@
#include <units/time.h>
#include <wpi/Demangle.h>
#include <wpi/SmallSet.h>
#include <wpi/deprecated.h>
#include <wpi/span.h>
#include "frc2/command/Subsystem.h"

View File

@@ -4,6 +4,8 @@
#pragma once
#include <wpi/deprecated.h>
#include "frc/AnalogAccelerometer.h"
#include "frc/PIDSource.h"

View File

@@ -4,6 +4,8 @@
#pragma once
#include <wpi/deprecated.h>
#include "frc/AnalogGyro.h"
#include "frc/PIDSource.h"

View File

@@ -4,6 +4,8 @@
#pragma once
#include <wpi/deprecated.h>
#include "frc/AnalogInput.h"
#include "frc/PIDSource.h"

View File

@@ -4,6 +4,8 @@
#pragma once
#include <wpi/deprecated.h>
#include "frc/AnalogPotentiometer.h"
#include "frc/PIDSource.h"

View File

@@ -4,6 +4,8 @@
#pragma once
#include <wpi/deprecated.h>
#include "frc/Encoder.h"
#include "frc/PIDSource.h"

View File

@@ -4,6 +4,7 @@
#pragma once
#include <wpi/deprecated.h>
#include <wpi/sendable/Sendable.h>
#include <wpi/sendable/SendableHelper.h>

View File

@@ -4,6 +4,8 @@
#pragma once
#include <wpi/deprecated.h>
#include "frc/PIDSource.h"
#include "frc/Ultrasonic.h"

View File

@@ -34,14 +34,6 @@ Compressor::~Compressor() {
}
}
void Compressor::Start() {
EnableDigital();
}
void Compressor::Stop() {
Disable();
}
bool Compressor::Enabled() const {
return IsEnabled();
}

View File

@@ -233,12 +233,6 @@ Instance::~Instance() {
}
}
DriverStation& DriverStation::GetInstance() {
::GetInstance();
static DriverStation instance;
return instance;
}
bool DriverStation::GetStickButton(int stick, int button) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
@@ -504,20 +498,12 @@ bool DriverStation::IsAutonomousEnabled() {
return controlWord.autonomous && controlWord.enabled;
}
bool DriverStation::IsOperatorControl() {
return IsTeleop();
}
bool DriverStation::IsTeleop() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return !(controlWord.autonomous || controlWord.test);
}
bool DriverStation::IsOperatorControlEnabled() {
return IsTeleopEnabled();
}
bool DriverStation::IsTeleopEnabled() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
@@ -671,10 +657,6 @@ void DriverStation::InAutonomous(bool entering) {
::GetInstance().userInAutonomous = entering;
}
void DriverStation::InOperatorControl(bool entering) {
InTeleop(entering);
}
void DriverStation::InTeleop(bool entering) {
::GetInstance().userInTeleop = entering;
}

View File

@@ -16,9 +16,6 @@
using namespace frc;
IterativeRobotBase::IterativeRobotBase(double period)
: IterativeRobotBase(units::second_t(period)) {}
IterativeRobotBase::IterativeRobotBase(units::second_t period)
: m_period(period),
m_watchdog(period, [this] { PrintLoopOverrunMessage(); }) {}

View File

@@ -38,12 +38,6 @@ void ResetPreferencesInstance() {
} // namespace frc::impl
#endif
Preferences* Preferences::GetInstance() {
::GetInstance();
static Preferences instance;
return &instance;
}
std::vector<std::string> Preferences::GetKeys() {
return ::GetInstance().table->GetKeys();
}
@@ -80,10 +74,6 @@ void Preferences::SetString(std::string_view key, std::string_view value) {
entry.SetPersistent();
}
void Preferences::PutString(std::string_view key, std::string_view value) {
SetString(key, value);
}
void Preferences::InitString(std::string_view key, std::string_view value) {
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultString(value);
@@ -96,10 +86,6 @@ void Preferences::SetInt(std::string_view key, int value) {
entry.SetPersistent();
}
void Preferences::PutInt(std::string_view key, int value) {
SetInt(key, value);
}
void Preferences::InitInt(std::string_view key, int value) {
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultDouble(value);
@@ -112,10 +98,6 @@ void Preferences::SetDouble(std::string_view key, double value) {
entry.SetPersistent();
}
void Preferences::PutDouble(std::string_view key, double value) {
SetDouble(key, value);
}
void Preferences::InitDouble(std::string_view key, double value) {
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultDouble(value);
@@ -128,10 +110,6 @@ void Preferences::SetFloat(std::string_view key, float value) {
entry.SetPersistent();
}
void Preferences::PutFloat(std::string_view key, float value) {
SetFloat(key, value);
}
void Preferences::InitFloat(std::string_view key, float value) {
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultDouble(value);
@@ -144,10 +122,6 @@ void Preferences::SetBoolean(std::string_view key, bool value) {
entry.SetPersistent();
}
void Preferences::PutBoolean(std::string_view key, bool value) {
SetBoolean(key, value);
}
void Preferences::InitBoolean(std::string_view key, bool value) {
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultBoolean(value);
@@ -160,10 +134,6 @@ void Preferences::SetLong(std::string_view key, int64_t value) {
entry.SetPersistent();
}
void Preferences::PutLong(std::string_view key, int64_t value) {
SetLong(key, value);
}
void Preferences::InitLong(std::string_view key, int64_t value) {
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultDouble(value);

View File

@@ -20,10 +20,6 @@ bool RobotState::IsEStopped() {
return DriverStation::IsEStopped();
}
bool RobotState::IsOperatorControl() {
return IsTeleop();
}
bool RobotState::IsTeleop() {
return DriverStation::IsTeleop();
}

View File

@@ -196,16 +196,6 @@ void SPI::SetSampleDataOnTrailingEdge() {
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
}
void SPI::SetSampleDataOnFalling() {
m_sampleOnTrailing = true;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
}
void SPI::SetSampleDataOnRising() {
m_sampleOnTrailing = false;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
}
void SPI::SetClockActiveLow() {
m_clockIdleHigh = true;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
@@ -278,10 +268,6 @@ void SPI::StartAutoRate(units::second_t period) {
FRC_CheckErrorStatus(status, "Port {}", m_port);
}
void SPI::StartAutoRate(double period) {
StartAutoRate(units::second_t(period));
}
void SPI::StartAutoTrigger(DigitalSource& source, bool rising, bool falling) {
int32_t status = 0;
HAL_StartSPIAutoTrigger(m_port, source.GetPortHandleForRouting(),
@@ -355,13 +341,6 @@ void SPI::InitAccumulator(units::second_t period, int cmd, int xferSize,
m_accum->m_notifier.StartPeriodic(period * kAccumulateDepth / 2);
}
void SPI::InitAccumulator(double period, int cmd, int xferSize, int validMask,
int validValue, int dataShift, int dataSize,
bool isSigned, bool bigEndian) {
InitAccumulator(units::second_t(period), cmd, xferSize, validMask, validValue,
dataShift, dataSize, isSigned, bigEndian);
}
void SPI::FreeAccumulator() {
m_accum.reset(nullptr);
FreeAuto();

View File

@@ -1,69 +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/SpeedControllerGroup.h"
#include <wpi/sendable/SendableBuilder.h>
#include <wpi/sendable/SendableRegistry.h>
using namespace frc;
// Can't use a delegated constructor here because of an MSVC bug.
// https://developercommunity.visualstudio.com/content/problem/583/compiler-bug-with-delegating-a-constructor.html
SpeedControllerGroup::SpeedControllerGroup(
std::vector<std::reference_wrapper<SpeedController>>&& speedControllers)
: m_speedControllers(std::move(speedControllers)) {
Initialize();
}
void SpeedControllerGroup::Initialize() {
for (auto& speedController : m_speedControllers) {
wpi::SendableRegistry::AddChild(this, &speedController.get());
}
static int instances = 0;
++instances;
wpi::SendableRegistry::Add(this, "SpeedControllerGroup", instances);
}
void SpeedControllerGroup::Set(double speed) {
for (auto speedController : m_speedControllers) {
speedController.get().Set(m_isInverted ? -speed : speed);
}
}
double SpeedControllerGroup::Get() const {
if (!m_speedControllers.empty()) {
return m_speedControllers.front().get().Get() * (m_isInverted ? -1 : 1);
}
return 0.0;
}
void SpeedControllerGroup::SetInverted(bool isInverted) {
m_isInverted = isInverted;
}
bool SpeedControllerGroup::GetInverted() const {
return m_isInverted;
}
void SpeedControllerGroup::Disable() {
for (auto speedController : m_speedControllers) {
speedController.get().Disable();
}
}
void SpeedControllerGroup::StopMotor() {
for (auto speedController : m_speedControllers) {
speedController.get().StopMotor();
}
}
void SpeedControllerGroup::InitSendable(wpi::SendableBuilder& builder) {
builder.SetSmartDashboardType("Speed Controller");
builder.SetActuator(true);
builder.SetSafeState([=] { StopMotor(); });
builder.AddDoubleProperty(
"Value", [=] { return Get(); }, [=](double value) { Set(value); });
}

View File

@@ -70,8 +70,6 @@ void TimedRobot::EndCompetition() {
HAL_StopNotifier(m_notifier, &status);
}
TimedRobot::TimedRobot(double period) : TimedRobot(units::second_t(period)) {}
TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) {
m_startTime = Timer::GetFPGATimestamp();
AddPeriodic([=] { LoopFunc(); }, period);

View File

@@ -65,10 +65,6 @@ bool Timer::HasElapsed(units::second_t period) const {
return Get() >= period;
}
bool Timer::HasPeriodPassed(units::second_t period) {
return AdvanceIfElapsed(period);
}
bool Timer::AdvanceIfElapsed(units::second_t period) {
if (Get() >= period) {
// Advance the start time by the period.

View File

@@ -12,20 +12,12 @@
#include <wpi/sendable/SendableRegistry.h>
#include "frc/MathUtil.h"
#include "frc/SpeedController.h"
#include "frc/motorcontrol/MotorController.h"
using namespace frc;
#if defined(_MSC_VER)
#pragma warning(disable : 4996) // was declared deprecated
#elif defined(__clang__)
#pragma clang diagnostic ignored "-Wdeprecated-declarations"
#elif defined(__GNUC__)
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
DifferentialDrive::DifferentialDrive(SpeedController& leftMotor,
SpeedController& rightMotor)
DifferentialDrive::DifferentialDrive(MotorController& leftMotor,
MotorController& rightMotor)
: m_leftMotor(&leftMotor), m_rightMotor(&rightMotor) {
wpi::SendableRegistry::AddChild(this, m_leftMotor);
wpi::SendableRegistry::AddChild(this, m_rightMotor);

View File

@@ -13,27 +13,19 @@
#include <wpi/sendable/SendableRegistry.h>
#include "frc/MathUtil.h"
#include "frc/SpeedController.h"
#include "frc/motorcontrol/MotorController.h"
using namespace frc;
#if defined(_MSC_VER)
#pragma warning(disable : 4996) // was declared deprecated
#elif defined(__clang__)
#pragma clang diagnostic ignored "-Wdeprecated-declarations"
#elif defined(__GNUC__)
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
KilloughDrive::KilloughDrive(SpeedController& leftMotor,
SpeedController& rightMotor,
SpeedController& backMotor)
KilloughDrive::KilloughDrive(MotorController& leftMotor,
MotorController& rightMotor,
MotorController& backMotor)
: KilloughDrive(leftMotor, rightMotor, backMotor, kDefaultLeftMotorAngle,
kDefaultRightMotorAngle, kDefaultBackMotorAngle) {}
KilloughDrive::KilloughDrive(SpeedController& leftMotor,
SpeedController& rightMotor,
SpeedController& backMotor, double leftMotorAngle,
KilloughDrive::KilloughDrive(MotorController& leftMotor,
MotorController& rightMotor,
MotorController& backMotor, double leftMotorAngle,
double rightMotorAngle, double backMotorAngle)
: m_leftMotor(&leftMotor),
m_rightMotor(&rightMotor),

View File

@@ -13,23 +13,15 @@
#include <wpi/sendable/SendableRegistry.h>
#include "frc/MathUtil.h"
#include "frc/SpeedController.h"
#include "frc/drive/Vector2d.h"
#include "frc/motorcontrol/MotorController.h"
using namespace frc;
#if defined(_MSC_VER)
#pragma warning(disable : 4996) // was declared deprecated
#elif defined(__clang__)
#pragma clang diagnostic ignored "-Wdeprecated-declarations"
#elif defined(__GNUC__)
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
MecanumDrive::MecanumDrive(SpeedController& frontLeftMotor,
SpeedController& rearLeftMotor,
SpeedController& frontRightMotor,
SpeedController& rearRightMotor)
MecanumDrive::MecanumDrive(MotorController& frontLeftMotor,
MotorController& rearLeftMotor,
MotorController& frontRightMotor,
MotorController& rearRightMotor)
: m_frontLeftMotor(&frontLeftMotor),
m_rearLeftMotor(&rearLeftMotor),
m_frontRightMotor(&frontRightMotor),

View File

@@ -10,7 +10,6 @@
#include <hal/FRCUsageReporting.h>
#include "frc/MathUtil.h"
#include "frc/motorcontrol/MotorController.h"
using namespace frc;
@@ -31,10 +30,6 @@ void RobotDriveBase::FeedWatchdog() {
Feed();
}
double RobotDriveBase::ApplyDeadband(double value, double deadband) {
return frc::ApplyDeadband(value, deadband);
}
void RobotDriveBase::Desaturate(wpi::span<double> wheelSpeeds) {
double maxMagnitude = std::abs(wheelSpeeds[0]);
for (size_t i = 1; i < wheelSpeeds.size(); i++) {

View File

@@ -75,12 +75,6 @@ std::shared_ptr<Component> Instance::GetOrAdd(wpi::Sendable* sendable) {
return data;
}
LiveWindow* LiveWindow::GetInstance() {
::GetInstance();
static LiveWindow instance;
return &instance;
}
void LiveWindow::SetEnabledCallback(std::function<void()> func) {
::GetInstance().enabled = func;
}

View File

@@ -2,12 +2,12 @@
// 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/SpeedController.h"
#include "frc/motorcontrol/MotorController.h"
#include <frc/RobotController.h>
using namespace frc;
void SpeedController::SetVoltage(units::volt_t output) {
void MotorController::SetVoltage(units::volt_t output) {
Set(output / units::volt_t(RobotController::GetInputVoltage()));
}

View File

@@ -192,18 +192,10 @@ bool RobotBase::IsAutonomousEnabled() const {
return DriverStation::IsAutonomousEnabled();
}
bool RobotBase::IsOperatorControl() const {
return DriverStation::IsTeleop();
}
bool RobotBase::IsTeleop() const {
return DriverStation::IsTeleop();
}
bool RobotBase::IsOperatorControlEnabled() const {
return DriverStation::IsTeleopEnabled();
}
bool RobotBase::IsTeleopEnabled() const {
return DriverStation::IsTeleopEnabled();
}

View File

@@ -58,24 +58,6 @@ class Compressor : public wpi::Sendable,
Compressor(Compressor&&) = default;
Compressor& operator=(Compressor&&) = default;
/**
* Starts closed-loop control. Note that closed loop control is enabled by
* default.
*
* @deprecated Use EnableDigital() instead.
*/
WPI_DEPRECATED("Use EnableDigital() instead")
void Start();
/**
* Stops closed-loop control. Note that closed loop control is enabled by
* default.
*
* @deprecated Use Disable() instead.
*/
WPI_DEPRECATED("Use Disable() instead")
void Stop();
/**
* Check if compressor output is active.
* To (re)enable the compressor use EnableDigital() or EnableAnalog(...).

View File

@@ -7,7 +7,6 @@
#include <string>
#include <units/time.h>
#include <wpi/deprecated.h>
namespace wpi::log {
class DataLog;
@@ -24,15 +23,6 @@ class DriverStation final {
enum Alliance { kRed, kBlue, kInvalid };
enum MatchType { kNone, kPractice, kQualification, kElimination };
/**
* Return a reference to the singleton DriverStation.
*
* @return Reference to the DS instance
* @deprecated Use the static methods
*/
WPI_DEPRECATED("Use static methods")
static DriverStation& GetInstance();
static constexpr int kJoystickPorts = 6;
/**
@@ -196,15 +186,6 @@ class DriverStation final {
*/
static bool IsAutonomousEnabled();
/**
* Check if the DS is commanding teleop mode.
*
* @return True if the robot is being commanded to be in teleop mode
* @deprecated Use IsTeleop() instead.
*/
WPI_DEPRECATED("Use IsTeleop() instead")
static bool IsOperatorControl();
/**
* Check if the DS is commanding teleop mode.
*
@@ -212,16 +193,6 @@ class DriverStation final {
*/
static bool IsTeleop();
/**
* Check if the DS is commanding teleop mode and if it has enabled the robot.
*
* @return True if the robot is being commanded to be in teleop mode and
* enabled.
* @deprecated Use IsTeleopEnabled() instead.
*/
WPI_DEPRECATED("Use IsTeleopEnabled() instead")
static bool IsOperatorControlEnabled();
/**
* Check if the DS is commanding teleop mode and if it has enabled the robot.
*
@@ -395,17 +366,6 @@ class DriverStation final {
*/
static void InAutonomous(bool entering);
/**
* Only to be used to tell the Driver Station what code you claim to be
* executing for diagnostic purposes only.
*
* @param entering If true, starting teleop code; if false, leaving teleop
* code.
* @deprecated Use InTeleop() instead.
*/
WPI_DEPRECATED("Use InTeleop() instead")
static void InOperatorControl(bool entering);
/**
* Only to be used to tell the Driver Station what code you claim to be
* executing for diagnostic purposes only.

View File

@@ -166,7 +166,9 @@ class Encoder : public CounterBase,
* scaled using the value from SetDistancePerPulse().
*
* @return Period in seconds of the most recent pulse.
* @deprecated Use getRate() in favor of this method.
*/
WPI_DEPRECATED("Use GetRate() in favor of this method")
units::second_t GetPeriod() const override;
/**
@@ -177,13 +179,12 @@ class Encoder : public CounterBase,
* to determine if the wheels or other shaft has stopped rotating.
* This method compensates for the decoding type.
*
* @deprecated Use SetMinRate() in favor of this method. This takes unscaled
* periods and SetMinRate() scales using value from
* SetDistancePerPulse().
*
* @param maxPeriod The maximum time between rising and falling edges before
* the FPGA will report the device stopped. This is expressed
* in seconds.
* @deprecated Use SetMinRate() in favor of this method. This takes unscaled
* periods and SetMinRate() scales using value from
* SetDistancePerPulse().
*/
WPI_DEPRECATED(
"Use SetMinRate() in favor of this method. This takes unscaled periods "

View File

@@ -5,7 +5,6 @@
#pragma once
#include <units/time.h>
#include <wpi/deprecated.h>
#include "frc/RobotBase.h"
#include "frc/Watchdog.h"
@@ -207,17 +206,6 @@ class IterativeRobotBase : public RobotBase {
*/
units::second_t GetPeriod() const;
/**
* Constructor for IterativeRobotBase.
*
* @param period Period in seconds.
*
* @deprecated Use IterativeRobotBase(units::second_t period) with unit-safety
* instead
*/
WPI_DEPRECATED("Use constructor with unit-safety instead.")
explicit IterativeRobotBase(double period);
/**
* Constructor for IterativeRobotBase.
*

View File

@@ -10,8 +10,6 @@
#include <string_view>
#include <vector>
#include <wpi/deprecated.h>
namespace frc {
/**
@@ -30,15 +28,6 @@ namespace frc {
*/
class Preferences {
public:
/**
* Get the one and only {@link Preferences} object.
*
* @return pointer to the {@link Preferences}
* @deprecated Use the static methods
*/
WPI_DEPRECATED("Use static methods")
static Preferences* GetInstance();
/**
* Returns a vector of all the keys.
*
@@ -119,18 +108,6 @@ class Preferences {
*/
static void SetString(std::string_view key, std::string_view value);
/**
* Puts the given string into the preferences table.
*
* The value may not have quotation marks, nor may the key have any whitespace
* nor an equals sign.
*
* @param key the key
* @param value the value
*/
WPI_DEPRECATED("Use SetString instead.")
static void PutString(std::string_view key, std::string_view value);
/**
* Puts the given string into the preferences table if it doesn't
* already exist.
@@ -147,17 +124,6 @@ class Preferences {
*/
static void SetInt(std::string_view key, int value);
/**
* Puts the given int into the preferences table.
*
* The key may not have any whitespace nor an equals sign.
*
* @param key the key
* @param value the value
*/
WPI_DEPRECATED("Use SetInt instead.")
static void PutInt(std::string_view key, int value);
/**
* Puts the given int into the preferences table if it doesn't
* already exist.
@@ -174,17 +140,6 @@ class Preferences {
*/
static void SetDouble(std::string_view key, double value);
/**
* Puts the given double into the preferences table.
*
* The key may not have any whitespace nor an equals sign.
*
* @param key the key
* @param value the value
*/
WPI_DEPRECATED("Use SetDouble instead.")
static void PutDouble(std::string_view key, double value);
/**
* Puts the given double into the preferences table if it doesn't
* already exist.
@@ -201,17 +156,6 @@ class Preferences {
*/
static void SetFloat(std::string_view key, float value);
/**
* Puts the given float into the preferences table.
*
* The key may not have any whitespace nor an equals sign.
*
* @param key the key
* @param value the value
*/
WPI_DEPRECATED("Use SetFloat instead.")
static void PutFloat(std::string_view key, float value);
/**
* Puts the given float into the preferences table if it doesn't
* already exist.
@@ -228,17 +172,6 @@ class Preferences {
*/
static void SetBoolean(std::string_view key, bool value);
/**
* Puts the given boolean into the preferences table.
*
* The key may not have any whitespace nor an equals sign.
*
* @param key the key
* @param value the value
*/
WPI_DEPRECATED("Use SetBoolean instead.")
static void PutBoolean(std::string_view key, bool value);
/**
* Puts the given boolean into the preferences table if it doesn't
* already exist.
@@ -255,17 +188,6 @@ class Preferences {
*/
static void SetLong(std::string_view key, int64_t value);
/**
* Puts the given long (int64_t) into the preferences table.
*
* The key may not have any whitespace nor an equals sign.
*
* @param key the key
* @param value the value
*/
WPI_DEPRECATED("Use SetLong instead.")
static void PutLong(std::string_view key, int64_t value);
/**
* Puts the given long into the preferences table if it doesn't
* already exist.

View File

@@ -11,7 +11,6 @@
#include <hal/HALBase.h>
#include <hal/Main.h>
#include <wpi/condition_variable.h>
#include <wpi/deprecated.h>
#include <wpi/mutex.h>
#include "frc/Errors.h"
@@ -151,16 +150,6 @@ class RobotBase {
*/
bool IsAutonomousEnabled() const;
/**
* Determine if the robot is currently in Operator Control mode.
*
* @return True if the robot is currently operating in Tele-Op mode as
* determined by the field controls.
* @deprecated Use IsTeleop() instead.
*/
WPI_DEPRECATED("Use IsTeleop() instead")
bool IsOperatorControl() const;
/**
* Determine if the robot is currently in Operator Control mode.
*
@@ -169,16 +158,6 @@ class RobotBase {
*/
bool IsTeleop() const;
/**
* Determine if the robot is current in Operator Control mode and enabled.
*
* @return True if the robot is currently operating in Tele-Op mode while
* enabled as determined by the field-controls.
* @deprecated Use IsTeleopEnabled() instead.
*/
WPI_DEPRECATED("Use IsTeleopEnabled() instead")
bool IsOperatorControlEnabled() const;
/**
* Determine if the robot is current in Operator Control mode and enabled.
*

View File

@@ -4,8 +4,6 @@
#pragma once
#include <wpi/deprecated.h>
namespace frc {
class RobotState {
@@ -15,8 +13,6 @@ class RobotState {
static bool IsDisabled();
static bool IsEnabled();
static bool IsEStopped();
WPI_DEPRECATED("Use IsTeleop() instead")
static bool IsOperatorControl();
static bool IsTeleop();
static bool IsAutonomous();
static bool IsTest();

View File

@@ -10,7 +10,6 @@
#include <hal/SPITypes.h>
#include <units/time.h>
#include <wpi/deprecated.h>
#include <wpi/span.h>
namespace frc {
@@ -76,26 +75,6 @@ class SPI {
*/
void SetSampleDataOnTrailingEdge();
/**
* Configure that the data is stable on the falling edge and the data
* changes on the rising edge.
*
* @deprecated Use SetSampleDataOnTrailingEdge() instead.
*
*/
WPI_DEPRECATED("Use SetSampleDataOnTrailingEdge instead.")
void SetSampleDataOnFalling();
/**
* Configure that the data is stable on the rising edge and the data
* changes on the falling edge.
*
* @deprecated Use SetSampleDataOnLeadingEdge() instead.
*
*/
WPI_DEPRECATED("Use SetSampleDataOnLeadingEdge instead")
void SetSampleDataOnRising();
/**
* Configure the clock output line to be active low.
* This is sometimes called clock polarity high or clock idle high.
@@ -189,19 +168,6 @@ class SPI {
*/
void StartAutoRate(units::second_t period);
/**
* Start running the automatic SPI transfer engine at a periodic rate.
*
* InitAuto() and SetAutoTransmitData() must be called before calling this
* function.
*
* @deprecated use unit-safe StartAutoRate(units::second_t period) instead.
*
* @param period period between transfers, in seconds (us resolution)
*/
WPI_DEPRECATED("Use StartAutoRate with unit-safety instead")
void StartAutoRate(double period);
/**
* Start running the automatic SPI transfer engine when a trigger occurs.
*
@@ -286,31 +252,6 @@ class SPI {
int validMask, int validValue, int dataShift,
int dataSize, bool isSigned, bool bigEndian);
/**
* Initialize the accumulator.
*
* @deprecated Use unit-safe version instead.
* InitAccumulator(units::second_t period, int cmd, int <!--
* --> xferSize, int validMask, int validValue, int dataShift, <!--
* --> int dataSize, bool isSigned, bool bigEndian)
*
* @param period Time between reads
* @param cmd SPI command to send to request data
* @param xferSize SPI transfer size, in bytes
* @param validMask Mask to apply to received data for validity checking
* @param validValue After valid_mask is applied, required matching value for
* validity checking
* @param dataShift Bit shift to apply to received data to get actual data
* value
* @param dataSize Size (in bits) of data field
* @param isSigned Is data field signed?
* @param bigEndian Is device big endian?
*/
WPI_DEPRECATED("Use InitAccumulator with unit-safety instead")
void InitAccumulator(double period, int cmd, int xferSize, int validMask,
int validValue, int dataShift, int dataSize,
bool isSigned, bool bigEndian);
/**
* Frees the accumulator.
*/

View File

@@ -1,74 +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 <units/voltage.h>
#include <wpi/deprecated.h>
namespace frc {
/**
* Interface for speed controlling devices.
*
* @deprecated Use MotorController.
*/
class WPI_DEPRECATED("use MotorController") SpeedController {
public:
virtual ~SpeedController() = default;
/**
* Common interface for setting the speed of a speed controller.
*
* @param speed The speed to set. Value should be between -1.0 and 1.0.
*/
virtual void Set(double speed) = 0;
/**
* Sets the voltage output of the SpeedController. Compensates for
* the current bus voltage to ensure that the desired voltage is output even
* if the battery voltage is below 12V - highly useful when the voltage
* outputs are "meaningful" (e.g. they come from a feedforward calculation).
*
* <p>NOTE: This function *must* be called regularly in order for voltage
* compensation to work properly - unlike the ordinary set function, it is not
* "set it and forget it."
*
* @param output The voltage to output.
*/
virtual void SetVoltage(units::volt_t output);
/**
* Common interface for getting the current set speed of a speed controller.
*
* @return The current set speed. Value is between -1.0 and 1.0.
*/
virtual double Get() const = 0;
/**
* Common interface for inverting direction of a speed controller.
*
* @param isInverted The state of inversion, true is inverted.
*/
virtual void SetInverted(bool isInverted) = 0;
/**
* Common interface for returning the inversion state of a speed controller.
*
* @return isInverted The state of inversion, true is inverted.
*/
virtual bool GetInverted() const = 0;
/**
* Common interface for disabling a motor.
*/
virtual void Disable() = 0;
/**
* Common interface to stop the motor until Set is called again.
*/
virtual void StopMotor() = 0;
};
} // namespace frc

View File

@@ -1,55 +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 <functional>
#include <vector>
#include <wpi/deprecated.h>
#include <wpi/sendable/Sendable.h>
#include <wpi/sendable/SendableHelper.h>
#include "frc/motorcontrol/MotorController.h"
namespace frc {
/**
* Allows multiple SpeedController objects to be linked together.
*
* @deprecated Use MotorControllerGroup.
*/
class WPI_DEPRECATED("use MotorControllerGroup") SpeedControllerGroup
: public wpi::Sendable,
public MotorController,
public wpi::SendableHelper<SpeedControllerGroup> {
public:
template <class... SpeedControllers>
explicit SpeedControllerGroup(SpeedController& speedController,
SpeedControllers&... speedControllers);
explicit SpeedControllerGroup(
std::vector<std::reference_wrapper<SpeedController>>&& speedControllers);
SpeedControllerGroup(SpeedControllerGroup&&) = default;
SpeedControllerGroup& operator=(SpeedControllerGroup&&) = default;
void Set(double speed) override;
double Get() const override;
void SetInverted(bool isInverted) override;
bool GetInverted() const override;
void Disable() override;
void StopMotor() override;
void InitSendable(wpi::SendableBuilder& builder) override;
private:
bool m_isInverted = false;
std::vector<std::reference_wrapper<SpeedController>> m_speedControllers;
void Initialize();
};
} // namespace frc
#include "frc/SpeedControllerGroup.inc"

View File

@@ -1,22 +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 <functional>
#include <vector>
#include "frc/SpeedControllerGroup.h"
namespace frc {
template <class... SpeedControllers>
SpeedControllerGroup::SpeedControllerGroup(
SpeedController& speedController, SpeedControllers&... speedControllers)
: m_speedControllers(std::vector<std::reference_wrapper<SpeedController>>{
speedController, speedControllers...}) {
Initialize();
}
} // namespace frc

View File

@@ -11,7 +11,6 @@
#include <hal/Types.h>
#include <units/math.h>
#include <units/time.h>
#include <wpi/deprecated.h>
#include <wpi/priority_queue.h>
#include "frc/IterativeRobotBase.h"
@@ -42,17 +41,6 @@ class TimedRobot : public IterativeRobotBase {
*/
void EndCompetition() override;
/**
* Constructor for TimedRobot.
*
* @deprecated use unit safe constructor instead.
* TimedRobot(units::second_t period = kDefaultPeriod)
*
* @param period Period in seconds.
*/
WPI_DEPRECATED("Use constructor with unit-safety instead.")
explicit TimedRobot(double period);
/**
* Constructor for TimedRobot.
*

View File

@@ -5,7 +5,6 @@
#pragma once
#include <units/time.h>
#include <wpi/deprecated.h>
namespace frc {
@@ -94,18 +93,6 @@ class Timer {
*/
bool HasElapsed(units::second_t period) const;
/**
* Check if the period specified has passed and if it has, advance the start
* time by that period. This is useful to decide if it's time to do periodic
* work without drifting later by the time it took to get around to checking.
*
* @param period The period to check for.
* @return True if the period has passed.
* @deprecated Use AdvanceIfElapsed() instead.
*/
WPI_DEPRECATED("Use AdvanceIfElapsed() instead.")
bool HasPeriodPassed(units::second_t period);
/**
* Check if the period specified has passed and if it has, advance the start
* time by that period. This is useful to decide if it's time to do periodic

View File

@@ -13,18 +13,7 @@
namespace frc {
#if defined(_MSC_VER)
#pragma warning(push)
#pragma warning(disable : 4996) // was declared deprecated
#elif defined(__clang__)
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Wdeprecated-declarations"
#elif defined(__GNUC__)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
class SpeedController;
class MotorController;
/**
* A class for driving differential drive/skid-steer drive platforms such as
@@ -120,7 +109,7 @@ class DifferentialDrive : public RobotDriveBase,
* To pass multiple motors per side, use a MotorControllerGroup. If a motor
* needs to be inverted, do so before passing it in.
*/
DifferentialDrive(SpeedController& leftMotor, SpeedController& rightMotor);
DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor);
~DifferentialDrive() override = default;
@@ -223,16 +212,8 @@ class DifferentialDrive : public RobotDriveBase,
void InitSendable(wpi::SendableBuilder& builder) override;
private:
SpeedController* m_leftMotor;
SpeedController* m_rightMotor;
MotorController* m_leftMotor;
MotorController* m_rightMotor;
};
#if defined(_MSC_VER)
#pragma warning(pop)
#elif defined(__clang__)
#pragma clang diagnostic pop
#elif defined(__GNUC__)
#pragma GCC diagnostic pop
#endif
} // namespace frc

View File

@@ -15,18 +15,7 @@
namespace frc {
#if defined(_MSC_VER)
#pragma warning(push)
#pragma warning(disable : 4996) // was declared deprecated
#elif defined(__clang__)
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Wdeprecated-declarations"
#elif defined(__GNUC__)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
class SpeedController;
class MotorController;
/**
* A class for driving Killough drive platforms.
@@ -88,8 +77,8 @@ class KilloughDrive : public RobotDriveBase,
* @param rightMotor The motor on the right corner.
* @param backMotor The motor on the back corner.
*/
KilloughDrive(SpeedController& leftMotor, SpeedController& rightMotor,
SpeedController& backMotor);
KilloughDrive(MotorController& leftMotor, MotorController& rightMotor,
MotorController& backMotor);
/**
* Construct a Killough drive with the given motors.
@@ -106,8 +95,8 @@ class KilloughDrive : public RobotDriveBase,
* @param backMotorAngle The angle of the back wheel's forward direction of
* travel.
*/
KilloughDrive(SpeedController& leftMotor, SpeedController& rightMotor,
SpeedController& backMotor, double leftMotorAngle,
KilloughDrive(MotorController& leftMotor, MotorController& rightMotor,
MotorController& backMotor, double leftMotorAngle,
double rightMotorAngle, double backMotorAngle);
~KilloughDrive() override = default;
@@ -173,9 +162,9 @@ class KilloughDrive : public RobotDriveBase,
void InitSendable(wpi::SendableBuilder& builder) override;
private:
SpeedController* m_leftMotor;
SpeedController* m_rightMotor;
SpeedController* m_backMotor;
MotorController* m_leftMotor;
MotorController* m_rightMotor;
MotorController* m_backMotor;
Vector2d m_leftVec;
Vector2d m_rightVec;
@@ -184,12 +173,4 @@ class KilloughDrive : public RobotDriveBase,
bool reported = false;
};
#if defined(_MSC_VER)
#pragma warning(pop)
#elif defined(__clang__)
#pragma clang diagnostic pop
#elif defined(__GNUC__)
#pragma GCC diagnostic pop
#endif
} // namespace frc

View File

@@ -14,18 +14,7 @@
namespace frc {
#if defined(_MSC_VER)
#pragma warning(push)
#pragma warning(disable : 4996) // was declared deprecated
#elif defined(__clang__)
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Wdeprecated-declarations"
#elif defined(__GNUC__)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
class SpeedController;
class MotorController;
/**
* A class for driving Mecanum drive platforms.
@@ -81,9 +70,9 @@ class MecanumDrive : public RobotDriveBase,
*
* If a motor needs to be inverted, do so before passing it in.
*/
MecanumDrive(SpeedController& frontLeftMotor, SpeedController& rearLeftMotor,
SpeedController& frontRightMotor,
SpeedController& rearRightMotor);
MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor,
MotorController& frontRightMotor,
MotorController& rearRightMotor);
~MecanumDrive() override = default;
@@ -148,20 +137,12 @@ class MecanumDrive : public RobotDriveBase,
void InitSendable(wpi::SendableBuilder& builder) override;
private:
SpeedController* m_frontLeftMotor;
SpeedController* m_rearLeftMotor;
SpeedController* m_frontRightMotor;
SpeedController* m_rearRightMotor;
MotorController* m_frontLeftMotor;
MotorController* m_rearLeftMotor;
MotorController* m_frontRightMotor;
MotorController* m_rearRightMotor;
bool reported = false;
};
#if defined(_MSC_VER)
#pragma warning(pop)
#elif defined(__clang__)
#pragma clang diagnostic pop
#elif defined(__GNUC__)
#pragma GCC diagnostic pop
#endif
} // namespace frc

View File

@@ -7,7 +7,6 @@
#include <memory>
#include <string>
#include <wpi/deprecated.h>
#include <wpi/span.h>
#include "frc/MotorSafety.h"
@@ -72,17 +71,6 @@ class RobotDriveBase : public MotorSafety {
std::string GetDescription() const override = 0;
protected:
/**
* Returns 0.0 if the given value is within the specified range around zero.
* The remaining range between the deadband and 1.0 is scaled from 0.0 to 1.0.
*
* @param value value to clip
* @param deadband range around zero
* @deprecated Use ApplyDeadband() in frc/MathUtil.h.
*/
WPI_DEPRECATED("Use ApplyDeadband() in frc/MathUtil.h")
static double ApplyDeadband(double value, double deadband);
/**
* Renormalize all wheel speeds if the magnitude of any wheel is greater than
* 1.0.

View File

@@ -6,8 +6,6 @@
#include <functional>
#include <wpi/deprecated.h>
namespace wpi {
class Sendable;
} // namespace wpi
@@ -20,17 +18,6 @@ namespace frc {
*/
class LiveWindow final {
public:
/**
* Get an instance of the LiveWindow main class.
*
* This is a singleton to guarantee that there is only a single instance
* regardless of how many times GetInstance is called.
* @deprecated Use the static methods unless guaranteeing LiveWindow is
* instantiated
*/
WPI_DEPRECATED("Use static methods")
static LiveWindow* GetInstance();
/**
* Set function to be called when LiveWindow is enabled.
*

View File

@@ -6,32 +6,66 @@
#include <units/voltage.h>
#include "frc/SpeedController.h"
namespace frc {
#if defined(_MSC_VER)
#pragma warning(push)
#pragma warning(disable : 4996) // was declared deprecated
#elif defined(__clang__)
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Wdeprecated-declarations"
#elif defined(__GNUC__)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
/**
* Interface for motor controlling devices.
*/
class MotorController : public SpeedController {};
class MotorController {
public:
virtual ~MotorController() = default;
#if defined(_MSC_VER)
#pragma warning(pop)
#elif defined(__clang__)
#pragma clang diagnostic pop
#elif defined(__GNUC__)
#pragma GCC diagnostic pop
#endif
/**
* Common interface for setting the speed of a motor controller.
*
* @param speed The speed to set. Value should be between -1.0 and 1.0.
*/
virtual void Set(double speed) = 0;
/**
* Sets the voltage output of the SpeedController. Compensates for
* the current bus voltage to ensure that the desired voltage is output even
* if the battery voltage is below 12V - highly useful when the voltage
* outputs are "meaningful" (e.g. they come from a feedforward calculation).
*
* <p>NOTE: This function *must* be called regularly in order for voltage
* compensation to work properly - unlike the ordinary set function, it is not
* "set it and forget it."
*
* @param output The voltage to output.
*/
virtual void SetVoltage(units::volt_t output);
/**
* Common interface for getting the current set speed of a motor controller.
*
* @return The current set speed. Value is between -1.0 and 1.0.
*/
virtual double Get() const = 0;
/**
* Common interface for inverting direction of a motor controller.
*
* @param isInverted The state of inversion, true is inverted.
*/
virtual void SetInverted(bool isInverted) = 0;
/**
* Common interface for returning the inversion state of a motor controller.
*
* @return isInverted The state of inversion, true is inverted.
*/
virtual bool GetInverted() const = 0;
/**
* Common interface for disabling a motor.
*/
virtual void Disable() = 0;
/**
* Common interface to stop the motor until Set is called again.
*/
virtual void StopMotor() = 0;
};
} // namespace frc

View File

@@ -8,7 +8,6 @@
#include <string_view>
#include <wpi/StringMap.h>
#include <wpi/deprecated.h>
#include "frc/smartdashboard/SendableChooserBase.h"
@@ -68,36 +67,6 @@ class SendableChooser : public SendableChooserBase {
*/
void SetDefaultOption(std::string_view name, T object);
/**
* Adds the given object to the list of options.
*
* On the SmartDashboard on the desktop, the object will appear as the given
* name.
*
* @deprecated use AddOption(std::string_view name, T object) instead.
*
* @param name the name of the option
* @param object the option
*/
WPI_DEPRECATED("use AddOption() instead")
void AddObject(std::string_view name, T object) { AddOption(name, object); }
/**
* Add the given object to the list of options and marks it as the default.
*
* Functionally, this is very close to AddOption() except that it will use
* this as the default option if none other is explicitly selected.
*
* @deprecated use SetDefaultOption(std::string_view name, T object) instead.
*
* @param name the name of the option
* @param object the option
*/
WPI_DEPRECATED("use SetDefaultOption() instead")
void AddDefault(std::string_view name, T object) {
SetDefaultOption(name, object);
}
/**
* Returns a copy of the selected option (a raw pointer U* if T =
* std::unique_ptr<U> or a std::weak_ptr<U> if T = std::shared_ptr<U>).

View File

@@ -62,34 +62,6 @@ public class Compressor implements Sendable, AutoCloseable {
m_module = null;
}
/**
* Start the compressor running in closed loop control mode.
*
* <p>Use the method in cases where you would like to manually stop and start the compressor for
* applications such as conserving battery or making sure that the compressor motor doesn't start
* during critical operations.
*
* @deprecated Use enableDigital() instead.
*/
@Deprecated(since = "2022", forRemoval = true)
public void start() {
enableDigital();
}
/**
* Stop the compressor from running in closed loop control mode.
*
* <p>Use the method in cases where you would like to manually stop and start the compressor for
* applications such as conserving battery or making sure that the compressor motor doesn't start
* during critical operations.
*
* @deprecated Use disable() instead.
*/
@Deprecated(since = "2022", forRemoval = true)
public void stop() {
disable();
}
/**
* Get the status of the compressor. To (re)enable the compressor use enableDigital() or
* enableAnalog(...).

View File

@@ -398,8 +398,6 @@ public final class DriverStation {
final JoystickLogSender[] m_joysticks;
}
private static DriverStation instance = new DriverStation();
// Joystick User Data
private static HALJoystickAxes[] m_joystickAxes = new HALJoystickAxes[kJoystickPorts];
private static HALJoystickPOVs[] m_joystickPOVs = new HALJoystickPOVs[kJoystickPorts];
@@ -448,17 +446,6 @@ public final class DriverStation {
private static final ControlWord m_controlWordCache;
private static long m_lastControlWordUpdate;
/**
* Gets an instance of the DriverStation.
*
* @return The DriverStation.
* @deprecated Use the static methods
*/
@Deprecated
public static DriverStation getInstance() {
return DriverStation.instance;
}
/**
* DriverStation constructor.
*
@@ -985,18 +972,6 @@ public final class DriverStation {
}
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be running in
* operator-controlled mode.
*
* @return True if operator-controlled mode should be enabled, false otherwise.
* @deprecated Use isTeleop() instead.
*/
@Deprecated(since = "2022", forRemoval = true)
public static boolean isOperatorControl() {
return isTeleop();
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be running in
* operator-controlled mode.
@@ -1007,18 +982,6 @@ public final class DriverStation {
return !(isAutonomous() || isTest());
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be running in
* operator-controller mode and enabled.
*
* @return True if operator-controlled mode should be set and the robot should be enabled.
* @deprecated Use isTeleopEnabled() instead.
*/
@Deprecated(since = "2022", forRemoval = true)
public static boolean isOperatorControlEnabled() {
return isTeleopEnabled();
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be running in
* operator-controller mode and enabled.
@@ -1334,18 +1297,6 @@ public final class DriverStation {
m_userInAutonomous = entering;
}
/**
* Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
* purposes only.
*
* @param entering If true, starting teleop code; if false, leaving teleop code
* @deprecated Use {@link #inTeleop(boolean)} instead.
*/
@Deprecated(since = "2022", forRemoval = true)
public static void inOperatorControl(boolean entering) {
m_userInTeleop = entering;
}
/**
* Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
* purposes only.

View File

@@ -370,8 +370,11 @@ public class Encoder implements CounterBase, Sendable, AutoCloseable {
*
* @param maxPeriod The maximum time between rising and falling edges before the FPGA will report
* the device stopped. This is expressed in seconds.
* @deprecated Use setMinRate() in favor of this method. This takes unscaled periods and
* setMinRate() scales using value from setDistancePerPulse().
*/
@Override
@Deprecated
public void setMaxPeriod(double maxPeriod) {
EncoderJNI.setEncoderMaxPeriod(m_encoder, maxPeriod);
}

View File

@@ -30,25 +30,9 @@ import java.util.Collection;
public final class Preferences {
/** The Preferences table name. */
private static final String TABLE_NAME = "Preferences";
/** The singleton instance. */
private static Preferences instance;
/** The network table. */
private static final NetworkTable m_table;
/**
* Returns the preferences instance.
*
* @return the preferences instance
* @deprecated Use the static methods
*/
@Deprecated
public static synchronized Preferences getInstance() {
if (instance == null) {
instance = new Preferences();
}
return instance;
}
/** Creates a preference class. */
private Preferences() {}
@@ -87,19 +71,6 @@ public final class Preferences {
entry.setPersistent();
}
/**
* Puts the given string into the preferences table.
*
* @param key the key
* @param value the value
* @throws NullPointerException if value is null
* @deprecated Use {@link #setString(String, String)}
*/
@Deprecated
public static void putString(String key, String value) {
setString(key, value);
}
/**
* Puts the given string into the preferences table if it doesn't already exist.
*
@@ -124,18 +95,6 @@ public final class Preferences {
entry.setPersistent();
}
/**
* Puts the given int into the preferences table.
*
* @param key the key
* @param value the value
* @deprecated Use {@link #setInt(String, int)}
*/
@Deprecated
public static void putInt(String key, int value) {
setInt(key, value);
}
/**
* Puts the given int into the preferences table if it doesn't already exist.
*
@@ -160,18 +119,6 @@ public final class Preferences {
entry.setPersistent();
}
/**
* Puts the given double into the preferences table.
*
* @param key the key
* @param value the value
* @deprecated Use {@link #setDouble(String, double)}
*/
@Deprecated
public static void putDouble(String key, double value) {
setDouble(key, value);
}
/**
* Puts the given double into the preferences table if it doesn't already exist.
*
@@ -196,18 +143,6 @@ public final class Preferences {
entry.setPersistent();
}
/**
* Puts the given float into the preferences table.
*
* @param key the key
* @param value the value
* @deprecated Use {@link #setFloat(String, float)}
*/
@Deprecated
public static void putFloat(String key, float value) {
setFloat(key, value);
}
/**
* Puts the given float into the preferences table if it doesn't already exist.
*
@@ -232,18 +167,6 @@ public final class Preferences {
entry.setPersistent();
}
/**
* Puts the given boolean into the preferences table.
*
* @param key the key
* @param value the value
* @deprecated Use {@link #setBoolean(String, boolean)}
*/
@Deprecated
public static void putBoolean(String key, boolean value) {
setBoolean(key, value);
}
/**
* Puts the given boolean into the preferences table if it doesn't already exist.
*
@@ -268,18 +191,6 @@ public final class Preferences {
entry.setPersistent();
}
/**
* Puts the given long into the preferences table.
*
* @param key the key
* @param value the value
* @deprecated Use {@link #setLong(String, long)}
*/
@Deprecated
public static void putLong(String key, long value) {
setLong(key, value);
}
/**
* Puts the given long into the preferences table if it doesn't already exist.
*

View File

@@ -234,18 +234,6 @@ public abstract class RobotBase implements AutoCloseable {
return DriverStation.isTest();
}
/**
* Determine if the robot is currently in Operator Control mode as determined by the field
* controls.
*
* @return True if the robot is currently operating in Tele-Op mode.
* @deprecated Use isTeleop() instead.
*/
@Deprecated(since = "2022", forRemoval = true)
public boolean isOperatorControl() {
return DriverStation.isTeleop();
}
/**
* Determine if the robot is currently in Operator Control mode as determined by the field
* controls.
@@ -256,18 +244,6 @@ public abstract class RobotBase implements AutoCloseable {
return DriverStation.isTeleop();
}
/**
* Determine if the robot is current in Operator Control mode and enabled as determined by the
* field controls.
*
* @return True if the robot is currently operating in Tele-Op mode while enabled.
* @deprecated Use isTeleopEnabled() instead.
*/
@Deprecated(since = "2022", forRemoval = true)
public boolean isOperatorControlEnabled() {
return DriverStation.isTeleopEnabled();
}
/**
* Determine if the robot is current in Operator Control mode and enabled as determined by the
* field controls.

View File

@@ -18,11 +18,6 @@ public final class RobotState {
return DriverStation.isEStopped();
}
@Deprecated
public static boolean isOperatorControl() {
return isTeleop();
}
public static boolean isTeleop() {
return DriverStation.isTeleop();
}

View File

@@ -123,30 +123,6 @@ public class SPI implements AutoCloseable {
SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
}
/**
* Configure that the data is stable on the falling edge and the data changes on the rising edge.
* Note this gets reversed is setClockActiveLow is set.
*
* @deprecated use {@link #setSampleDataOnTrailingEdge()} in most cases.
*/
@Deprecated
public final void setSampleDataOnFalling() {
m_sampleOnTrailing = 1;
SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
}
/**
* Configure that the data is stable on the rising edge and the data changes on the falling edge.
* Note this gets reversed is setClockActiveLow is set.
*
* @deprecated use {@link #setSampleDataOnLeadingEdge()} in most cases.
*/
@Deprecated
public final void setSampleDataOnRising() {
m_sampleOnTrailing = 0;
SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
}
/** Configure the chip select line to be active high. */
public final void setChipSelectActiveHigh() {
SPIJNI.spiSetChipSelectActiveHigh(m_port);

View File

@@ -81,48 +81,6 @@ public class SerialPort implements AutoCloseable {
}
}
/**
* Create an instance of a Serial Port class.
*
* <p>Prefer to use the constructor that doesn't take a port name, but in some cases the automatic
* detection might not work correctly.
*
* @param baudRate The baud rate to configure the serial port.
* @param port The Serial port to use
* @param portName The direct portName to use
* @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
* @param parity Select the type of parity checking to use.
* @param stopBits The number of stop bits to use as defined by the enum StopBits.
* @deprecated Will be removed for 2019
*/
@Deprecated
public SerialPort(
final int baudRate,
String portName,
Port port,
final int dataBits,
Parity parity,
StopBits stopBits) {
m_portHandle = SerialPortJNI.serialInitializePortDirect((byte) port.value, portName);
SerialPortJNI.serialSetBaudRate(m_portHandle, baudRate);
SerialPortJNI.serialSetDataBits(m_portHandle, (byte) dataBits);
SerialPortJNI.serialSetParity(m_portHandle, (byte) parity.value);
SerialPortJNI.serialSetStopBits(m_portHandle, (byte) stopBits.value);
// Set the default read buffer size to 1 to return bytes immediately
setReadBufferSize(1);
// Set the default timeout to 5 seconds.
setTimeout(5.0);
// Don't wait until the buffer is full to transmit.
setWriteBufferMode(WriteBufferMode.kFlushOnAccess);
disableTermination();
HAL.report(tResourceType.kResourceType_SerialPort, port.value + 1);
}
/**
* Create an instance of a Serial Port class.
*

View File

@@ -1,65 +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;
/**
* Interface for motor controlling devices.
*
* @deprecated Use {@link edu.wpi.first.wpilibj.motorcontrol.MotorController}.
*/
@Deprecated(since = "2022", forRemoval = true)
public interface SpeedController {
/**
* Common interface for setting the speed of a motor controller.
*
* @param speed The speed to set. Value should be between -1.0 and 1.0.
*/
void set(double speed);
/**
* Sets the voltage output of the MotorController. Compensates for the current bus voltage to
* ensure that the desired voltage is output even if the battery voltage is below 12V - highly
* useful when the voltage outputs are "meaningful" (e.g. they come from a feedforward
* calculation).
*
* <p>NOTE: This function *must* be called regularly in order for voltage compensation to work
* properly - unlike the ordinary set function, it is not "set it and forget it."
*
* @param outputVolts The voltage to output.
*/
default void setVoltage(double outputVolts) {
set(outputVolts / RobotController.getBatteryVoltage());
}
/**
* Common interface for getting the current set speed of a motor controller.
*
* @return The current set speed. Value is between -1.0 and 1.0.
*/
double get();
/**
* Common interface for inverting direction of a motor controller.
*
* @param isInverted The state of inversion true is inverted.
*/
void setInverted(boolean isInverted);
/**
* Common interface for returning if a motor controller is in the inverted state or not.
*
* @return isInverted The state of the inversion true is inverted.
*/
boolean getInverted();
/** Disable the motor controller. */
void disable();
/**
* Stops motor movement. Motor can be moved again by calling set without having to re-enable the
* motor.
*/
void stopMotor();
}

View File

@@ -1,103 +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;
import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import java.util.Arrays;
/**
* Allows multiple {@link SpeedController} objects to be linked together.
*
* @deprecated Use {@link edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup}.
*/
@Deprecated(since = "2022", forRemoval = true)
@SuppressWarnings("removal")
public class SpeedControllerGroup implements MotorController, Sendable, AutoCloseable {
private boolean m_isInverted;
private final SpeedController[] m_speedControllers;
private static int instances;
/**
* Create a new SpeedControllerGroup with the provided SpeedControllers.
*
* @param speedController The first SpeedController to add.
* @param speedControllers The SpeedControllers to add
*/
public SpeedControllerGroup(
SpeedController speedController, SpeedController... speedControllers) {
m_speedControllers = new SpeedController[speedControllers.length + 1];
m_speedControllers[0] = speedController;
System.arraycopy(speedControllers, 0, m_speedControllers, 1, speedControllers.length);
init();
}
public SpeedControllerGroup(SpeedController[] speedControllers) {
m_speedControllers = Arrays.copyOf(speedControllers, speedControllers.length);
init();
}
private void init() {
for (SpeedController controller : m_speedControllers) {
SendableRegistry.addChild(this, controller);
}
instances++;
SendableRegistry.addLW(this, "MotorControllerGroup", instances);
}
@Override
public void close() {
SendableRegistry.remove(this);
}
@Override
public void set(double speed) {
for (SpeedController speedController : m_speedControllers) {
speedController.set(m_isInverted ? -speed : speed);
}
}
@Override
public double get() {
if (m_speedControllers.length > 0) {
return m_speedControllers[0].get() * (m_isInverted ? -1 : 1);
}
return 0.0;
}
@Override
public void setInverted(boolean isInverted) {
m_isInverted = isInverted;
}
@Override
public boolean getInverted() {
return m_isInverted;
}
@Override
public void disable() {
for (SpeedController speedController : m_speedControllers) {
speedController.disable();
}
}
@Override
public void stopMotor() {
for (SpeedController speedController : m_speedControllers) {
speedController.stopMotor();
}
}
@Override
public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("Motor Controller");
builder.setActuator(true);
builder.setSafeState(this::stopMotor);
builder.addDoubleProperty("Value", this::get, this::set);
}
}

View File

@@ -121,20 +121,6 @@ public class Timer {
return get() >= seconds;
}
/**
* Check if the period specified has passed and if it has, advance the start time by that period.
* This is useful to decide if it's time to do periodic work without drifting later by the time it
* took to get around to checking.
*
* @param period The period to check for (in seconds).
* @return Whether the period has passed.
* @deprecated Use advanceIfElapsed() instead.
*/
@Deprecated(since = "2022", forRemoval = true)
public boolean hasPeriodPassed(double period) {
return advanceIfElapsed(period);
}
/**
* Check if the period specified has passed and if it has, advance the start time by that period.
* This is useful to decide if it's time to do periodic work without drifting later by the time it

View File

@@ -13,7 +13,7 @@ import edu.wpi.first.math.MathUtil;
import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
/**
* A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive
@@ -87,12 +87,11 @@ import edu.wpi.first.wpilibj.SpeedController;
* <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default. The tankDrive, arcadeDrive,
* or curvatureDrive methods should be called periodically to avoid Motor Safety timeouts.
*/
@SuppressWarnings("removal")
public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoCloseable {
private static int instances;
private final SpeedController m_leftMotor;
private final SpeedController m_rightMotor;
private final MotorController m_leftMotor;
private final MotorController m_rightMotor;
private boolean m_reported;
@@ -131,7 +130,7 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC
* @param leftMotor Left motor.
* @param rightMotor Right motor.
*/
public DifferentialDrive(SpeedController leftMotor, SpeedController rightMotor) {
public DifferentialDrive(MotorController leftMotor, MotorController rightMotor) {
requireNonNull(leftMotor, "Left motor cannot be null");
requireNonNull(rightMotor, "Right motor cannot be null");

View File

@@ -13,7 +13,7 @@ import edu.wpi.first.math.MathUtil;
import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
/**
* A class for driving Killough drive platforms.
@@ -43,7 +43,6 @@ import edu.wpi.first.wpilibj.SpeedController;
* <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default. The driveCartesian or
* drivePolar methods should be called periodically to avoid Motor Safety timeouts.
*/
@SuppressWarnings("removal")
public class KilloughDrive extends RobotDriveBase implements Sendable, AutoCloseable {
public static final double kDefaultLeftMotorAngle = 60.0;
public static final double kDefaultRightMotorAngle = 120.0;
@@ -51,9 +50,9 @@ public class KilloughDrive extends RobotDriveBase implements Sendable, AutoClose
private static int instances;
private SpeedController m_leftMotor;
private SpeedController m_rightMotor;
private SpeedController m_backMotor;
private MotorController m_leftMotor;
private MotorController m_rightMotor;
private MotorController m_backMotor;
private Vector2d m_leftVec;
private Vector2d m_rightVec;
@@ -102,7 +101,7 @@ public class KilloughDrive extends RobotDriveBase implements Sendable, AutoClose
* @param backMotor The motor on the back corner.
*/
public KilloughDrive(
SpeedController leftMotor, SpeedController rightMotor, SpeedController backMotor) {
MotorController leftMotor, MotorController rightMotor, MotorController backMotor) {
this(
leftMotor,
rightMotor,
@@ -125,9 +124,9 @@ public class KilloughDrive extends RobotDriveBase implements Sendable, AutoClose
* @param backMotorAngle The angle of the back wheel's forward direction of travel.
*/
public KilloughDrive(
SpeedController leftMotor,
SpeedController rightMotor,
SpeedController backMotor,
MotorController leftMotor,
MotorController rightMotor,
MotorController backMotor,
double leftMotorAngle,
double rightMotorAngle,
double backMotorAngle) {

View File

@@ -13,7 +13,7 @@ import edu.wpi.first.math.MathUtil;
import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
/**
* A class for driving Mecanum drive platforms.
@@ -50,14 +50,13 @@ import edu.wpi.first.wpilibj.SpeedController;
* <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default. The driveCartesian or
* drivePolar methods should be called periodically to avoid Motor Safety timeouts.
*/
@SuppressWarnings("removal")
public class MecanumDrive extends RobotDriveBase implements Sendable, AutoCloseable {
private static int instances;
private final SpeedController m_frontLeftMotor;
private final SpeedController m_rearLeftMotor;
private final SpeedController m_frontRightMotor;
private final SpeedController m_rearRightMotor;
private final MotorController m_frontLeftMotor;
private final MotorController m_rearLeftMotor;
private final MotorController m_frontRightMotor;
private final MotorController m_rearRightMotor;
private boolean m_reported;
@@ -103,10 +102,10 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea
* @param rearRightMotor The motor on the rear-right corner.
*/
public MecanumDrive(
SpeedController frontLeftMotor,
SpeedController rearLeftMotor,
SpeedController frontRightMotor,
SpeedController rearRightMotor) {
MotorController frontLeftMotor,
MotorController rearLeftMotor,
MotorController frontRightMotor,
MotorController rearRightMotor) {
requireNonNull(frontLeftMotor, "Front-left motor cannot be null");
requireNonNull(rearLeftMotor, "Rear-left motor cannot be null");
requireNonNull(frontRightMotor, "Front-right motor cannot be null");

View File

@@ -4,7 +4,6 @@
package edu.wpi.first.wpilibj.drive;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.MotorSafety;
/**
@@ -81,20 +80,6 @@ public abstract class RobotDriveBase extends MotorSafety {
@Override
public abstract String getDescription();
/**
* Returns 0.0 if the given value is within the specified range around zero. The remaining range
* between the deadband and 1.0 is scaled from 0.0 to 1.0.
*
* @param value value to clip
* @param deadband range around zero
* @return The value after the deadband is applied.
* @deprecated Use MathUtil.applyDeadband(double,double).
*/
@Deprecated(since = "2021", forRemoval = true)
protected static double applyDeadband(double value, double deadband) {
return MathUtil.applyDeadband(value, deadband);
}
/**
* Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
*

View File

@@ -5,17 +5,14 @@
package edu.wpi.first.wpilibj.motorcontrol;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.SpeedController;
/** Interface for motor controlling devices. */
@SuppressWarnings("removal")
public interface MotorController extends SpeedController {
public interface MotorController {
/**
* Common interface for setting the speed of a motor controller.
*
* @param speed The speed to set. Value should be between -1.0 and 1.0.
*/
@Override
void set(double speed);
/**
@@ -29,7 +26,6 @@ public interface MotorController extends SpeedController {
*
* @param outputVolts The voltage to output.
*/
@Override
default void setVoltage(double outputVolts) {
set(outputVolts / RobotController.getBatteryVoltage());
}
@@ -39,7 +35,6 @@ public interface MotorController extends SpeedController {
*
* @return The current set speed. Value is between -1.0 and 1.0.
*/
@Override
double get();
/**
@@ -47,7 +42,6 @@ public interface MotorController extends SpeedController {
*
* @param isInverted The state of inversion true is inverted.
*/
@Override
void setInverted(boolean isInverted);
/**
@@ -55,17 +49,14 @@ public interface MotorController extends SpeedController {
*
* @return isInverted The state of the inversion true is inverted.
*/
@Override
boolean getInverted();
/** Disable the motor controller. */
@Override
void disable();
/**
* Stops motor movement. Motor can be moved again by calling set without having to re-enable the
* motor.
*/
@Override
void stopMotor();
}

View File

@@ -426,14 +426,7 @@ public class DifferentialDrivetrainSim {
public enum KitbotWheelSize {
kSixInch(Units.inchesToMeters(6)),
kEightInch(Units.inchesToMeters(8)),
kTenInch(Units.inchesToMeters(10)),
@Deprecated
SixInch(Units.inchesToMeters(6)),
@Deprecated
EightInch(Units.inchesToMeters(8)),
@Deprecated
TenInch(Units.inchesToMeters(10));
kTenInch(Units.inchesToMeters(10));
@SuppressWarnings("MemberName")
public final double value;

View File

@@ -69,18 +69,6 @@ public class SendableChooser<V> implements NTSendable, AutoCloseable {
m_map.put(name, object);
}
/**
* Adds the given object to the list of options.
*
* @param name the name of the option
* @param object the option
* @deprecated Use {@link #addOption(String, Object)} instead.
*/
@Deprecated
public void addObject(String name, V object) {
addOption(name, object);
}
/**
* Adds the given object to the list of options and marks it as the default. Functionally, this is
* very close to {@link #addOption(String, Object)} except that it will use this as the default
@@ -96,18 +84,6 @@ public class SendableChooser<V> implements NTSendable, AutoCloseable {
addOption(name, object);
}
/**
* Adds the given object to the list of options and marks it as the default.
*
* @param name the name of the option
* @param object the option
* @deprecated Use {@link #setDefaultOption(String, Object)} instead.
*/
@Deprecated
public void addDefault(String name, V object) {
setDefaultOption(name, object);
}
/**
* Returns the selected option. If there is none selected, it will return the default. If there is
* none selected and no default, then it will return {@code null}.

View File

@@ -1,26 +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.vision;
import org.opencv.core.Mat;
/**
* A vision pipeline is responsible for running a group of OpenCV algorithms to extract data from an
* image.
*
* @see VisionRunner
* @see VisionThread
* @deprecated Replaced with edu.wpi.first.vision.VisionPipeline
*/
@Deprecated
public interface VisionPipeline {
/**
* Processes the image input and sets the result objects. Implementations should make these
* objects accessible.
*
* @param image The image to process.
*/
void process(Mat image);
}

View File

@@ -1,123 +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.vision;
import edu.wpi.first.cameraserver.CameraServerSharedStore;
import edu.wpi.first.cscore.CvSink;
import edu.wpi.first.cscore.VideoSource;
import org.opencv.core.Mat;
/**
* A vision runner is a convenient wrapper object to make it easy to run vision pipelines from robot
* code. The easiest way to use this is to run it in a {@link VisionThread} and use the listener to
* take snapshots of the pipeline's outputs.
*
* @see VisionPipeline
* @see VisionThread
* @see <a href="package-summary.html">vision</a>
* @deprecated Replaced with edu.wpi.first.vision.VisionRunner
*/
@Deprecated
public class VisionRunner<P extends VisionPipeline> {
private final CvSink m_cvSink = new CvSink("VisionRunner CvSink");
private final P m_pipeline;
private final Mat m_image = new Mat();
private final Listener<? super P> m_listener;
private volatile boolean m_enabled = true;
/**
* Listener interface for a callback that should run after a pipeline has processed its input.
*
* @param <P> the type of the pipeline this listener is for
*/
@FunctionalInterface
public interface Listener<P extends VisionPipeline> {
/**
* Called when the pipeline has run. This shouldn't take much time to run because it will delay
* later calls to the pipeline's {@link VisionPipeline#process process} method. Copying the
* outputs and code that uses the copies should be <i>synchronized</i> on the same mutex to
* prevent multiple threads from reading and writing to the same memory at the same time.
*
* @param pipeline the vision pipeline that ran
*/
void copyPipelineOutputs(P pipeline);
}
/**
* Creates a new vision runner. It will take images from the {@code videoSource}, send them to the
* {@code pipeline}, and call the {@code listener} when the pipeline has finished to alert user
* code when it is safe to access the pipeline's outputs.
*
* @param videoSource the video source to use to supply images for the pipeline
* @param pipeline the vision pipeline to run
* @param listener a function to call after the pipeline has finished running
*/
public VisionRunner(VideoSource videoSource, P pipeline, Listener<? super P> listener) {
this.m_pipeline = pipeline;
this.m_listener = listener;
m_cvSink.setSource(videoSource);
}
/**
* Runs the pipeline one time, giving it the next image from the video source specified in the
* constructor. This will block until the source either has an image or throws an error. If the
* source successfully supplied a frame, the pipeline's image input will be set, the pipeline will
* run, and the listener specified in the constructor will be called to notify it that the
* pipeline ran.
*
* <p>This method is exposed to allow teams to add additional functionality or have their own ways
* to run the pipeline. Most teams, however, should just use {@link #runForever} in its own thread
* using a {@link VisionThread}.
*/
public void runOnce() {
Long id = CameraServerSharedStore.getCameraServerShared().getRobotMainThreadId();
if (id != null && Thread.currentThread().getId() == id) {
throw new IllegalStateException(
"VisionRunner.runOnce() cannot be called from the main robot thread");
}
runOnceInternal();
}
private void runOnceInternal() {
long frameTime = m_cvSink.grabFrame(m_image);
if (frameTime == 0) {
// There was an error, report it
String error = m_cvSink.getError();
CameraServerSharedStore.getCameraServerShared().reportDriverStationError(error);
} else {
// No errors, process the image
m_pipeline.process(m_image);
m_listener.copyPipelineOutputs(m_pipeline);
}
}
/**
* A convenience method that calls {@link #runOnce()} in an infinite loop. This must be run in a
* dedicated thread, and cannot be used in the main robot thread because it will freeze the robot
* program.
*
* <p><strong>Do not call this method directly from the main thread.</strong>
*
* @throws IllegalStateException if this is called from the main robot thread
* @see VisionThread
*/
public void runForever() {
Long id = CameraServerSharedStore.getCameraServerShared().getRobotMainThreadId();
if (id != null && Thread.currentThread().getId() == id) {
throw new IllegalStateException(
"VisionRunner.runForever() cannot be called from the main robot thread");
}
while (m_enabled && !Thread.interrupted()) {
runOnceInternal();
}
}
/** Stop a RunForever() loop. */
public void stop() {
m_enabled = false;
}
}

View File

@@ -1,44 +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.vision;
import edu.wpi.first.cscore.VideoSource;
/**
* A vision thread is a special thread that runs a vision pipeline. It is a <i>daemon</i> thread; it
* does not prevent the program from exiting when all other non-daemon threads have finished
* running.
*
* @see VisionPipeline
* @see VisionRunner
* @see Thread#setDaemon(boolean)
* @deprecated Replaced with edu.wpi.first.vision.VisionThread
*/
@Deprecated
public class VisionThread extends Thread {
/**
* Creates a vision thread that continuously runs a {@link VisionPipeline}.
*
* @param visionRunner the runner for a vision pipeline
*/
public VisionThread(VisionRunner<?> visionRunner) {
super(visionRunner::runForever, "WPILib Vision Thread");
setDaemon(true);
}
/**
* Creates a new vision thread that continuously runs the given vision pipeline. This is
* equivalent to {@code new VisionThread(new VisionRunner<>(videoSource, pipeline, listener))}.
*
* @param videoSource the source for images the pipeline should process
* @param pipeline the pipeline to run
* @param listener the listener to copy outputs from the pipeline after it runs
* @param <P> the type of the pipeline
*/
public <P extends VisionPipeline> VisionThread(
VideoSource videoSource, P pipeline, VisionRunner.Listener<? super P> listener) {
this(new VisionRunner<>(videoSource, pipeline, listener));
}
}

View File

@@ -1,86 +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.
/**
* Classes in the {@code edu.wpi.first.wpilibj.vision} package are designed to simplify using OpenCV
* vision processing code from a robot program.
*
* <p>An example use case for grabbing a yellow tote from 2015 in autonomous: <br>
*
* <pre><code>
* public class Robot extends IterativeRobot
* implements VisionRunner.Listener&lt;MyFindTotePipeline&gt; {
*
* // A USB camera connected to the roboRIO.
* private {@link edu.wpi.first.cscore.VideoSource VideoSource} usbCamera;
*
* // A vision pipeline. This could be handwritten or generated by GRIP.
* // This has to implement {@link edu.wpi.first.wpilibj.vision.VisionPipeline}.
* // For this example, assume that it's perfect and will always see the tote.
* private MyFindTotePipeline findTotePipeline;
* private {@link edu.wpi.first.wpilibj.vision.VisionThread} findToteThread;
*
* // The object to synchronize on to make sure the vision thread doesn't
* // write to variables the main thread is using.
* private final Object visionLock = new Object();
*
* // The pipeline outputs we want
* private boolean pipelineRan = false; // lets us know when the pipeline has actually run
* private double angleToTote = 0;
* private double distanceToTote = 0;
*
* {@literal @}Override
* public void {@link edu.wpi.first.wpilibj.vision.VisionRunner.Listener#copyPipelineOutputs
* copyPipelineOutputs(MyFindTotePipeline pipeline)} {
* synchronized (visionLock) {
* // Take a snapshot of the pipeline's output because
* // it may have changed the next time this method is called!
* this.pipelineRan = true;
* this.angleToTote = pipeline.getAngleToTote();
* this.distanceToTote = pipeline.getDistanceToTote();
* }
* }
*
* {@literal @}Override
* public void robotInit() {
* usbCamera = CameraServer.startAutomaticCapture(0);
* findTotePipeline = new MyFindTotePipeline();
* findToteThread = new VisionThread(usbCamera, findTotePipeline, this);
* }
*
* {@literal @}Override
* public void autonomousInit() {
* findToteThread.start();
* }
*
* {@literal @}Override
* public void autonomousPeriodic() {
* double angle;
* double distance;
* synchronized (visionLock) {
* if (!pipelineRan) {
* // Wait until the pipeline has run
* return;
* }
* // Copy the outputs to make sure they're all from the same run
* angle = this.angleToTote;
* distance = this.distanceToTote;
* }
* if (!aimedAtTote()) {
* turnToAngle(angle);
* } else if (!droveToTote()) {
* driveDistance(distance);
* } else if (!grabbedTote()) {
* grabTote();
* } else {
* // Tote was grabbed and we're done!
* return;
* }
* }
*
* }
* </code></pre>
*/
@java.lang.Deprecated
package edu.wpi.first.wpilibj.vision;

View File

@@ -30,7 +30,6 @@ import org.junit.jupiter.params.ParameterizedTest;
import org.junit.jupiter.params.provider.MethodSource;
class PreferencesTest {
private final Preferences m_prefs = Preferences.getInstance();
private final NetworkTable m_table = NetworkTableInstance.getDefault().getTable("Preferences");
private static final String kFilename = "networktables.ini";
@@ -66,7 +65,7 @@ class PreferencesTest {
@Test
void removeAllTest() {
m_prefs.removeAll();
Preferences.removeAll();
Set<String> keys = m_table.getKeys();
keys.remove(".type");
@@ -79,37 +78,37 @@ class PreferencesTest {
@ParameterizedTest
@MethodSource("defaultKeyProvider")
void defaultKeysTest(String key) {
assertTrue(m_prefs.containsKey(key));
assertTrue(Preferences.containsKey(key));
}
@ParameterizedTest
@MethodSource("defaultKeyProvider")
void defaultKeysAllTest(String key) {
assertTrue(m_prefs.getKeys().contains(key));
assertTrue(Preferences.getKeys().contains(key));
}
@Test
void defaultValueTest() {
assertAll(
() -> assertEquals(172L, m_prefs.getLong("checkedValueLong", 0)),
() -> assertEquals(0.2, m_prefs.getDouble("checkedValueDouble", 0), 1e-6),
() -> assertEquals("Hello. How are you?", m_prefs.getString("checkedValueString", "")),
() -> assertEquals(2, m_prefs.getInt("checkedValueInt", 0)),
() -> assertEquals(3.4, m_prefs.getFloat("checkedValueFloat", 0), 1e-6),
() -> assertFalse(m_prefs.getBoolean("checkedValueBoolean", true)));
() -> assertEquals(172L, Preferences.getLong("checkedValueLong", 0)),
() -> assertEquals(0.2, Preferences.getDouble("checkedValueDouble", 0), 1e-6),
() -> assertEquals("Hello. How are you?", Preferences.getString("checkedValueString", "")),
() -> assertEquals(2, Preferences.getInt("checkedValueInt", 0)),
() -> assertEquals(3.4, Preferences.getFloat("checkedValueFloat", 0), 1e-6),
() -> assertFalse(Preferences.getBoolean("checkedValueBoolean", true)));
}
@Test
void backupTest() {
m_prefs.removeAll();
Preferences.removeAll();
assertAll(
() -> assertEquals(0, m_prefs.getLong("checkedValueLong", 0)),
() -> assertEquals(0, m_prefs.getDouble("checkedValueDouble", 0), 1e-6),
() -> assertEquals("", m_prefs.getString("checkedValueString", "")),
() -> assertEquals(0, m_prefs.getInt("checkedValueInt", 0)),
() -> assertEquals(0, m_prefs.getFloat("checkedValueFloat", 0), 1e-6),
() -> assertTrue(m_prefs.getBoolean("checkedValueBoolean", true)));
() -> assertEquals(0, Preferences.getLong("checkedValueLong", 0)),
() -> assertEquals(0, Preferences.getDouble("checkedValueDouble", 0), 1e-6),
() -> assertEquals("", Preferences.getString("checkedValueString", "")),
() -> assertEquals(0, Preferences.getInt("checkedValueInt", 0)),
() -> assertEquals(0, Preferences.getFloat("checkedValueFloat", 0), 1e-6),
() -> assertTrue(Preferences.getBoolean("checkedValueBoolean", true)));
}
@Nested
@@ -119,10 +118,10 @@ class PreferencesTest {
final String key = "test";
final int value = 123;
m_prefs.putInt(key, value);
Preferences.setInt(key, value);
assertAll(
() -> assertEquals(value, m_prefs.getInt(key, -1)),
() -> assertEquals(value, Preferences.getInt(key, -1)),
() -> assertEquals(value, m_table.getEntry(key).getNumber(-1).intValue()));
}
@@ -131,10 +130,10 @@ class PreferencesTest {
final String key = "test";
final long value = 190L;
m_prefs.putLong(key, value);
Preferences.setLong(key, value);
assertAll(
() -> assertEquals(value, m_prefs.getLong(key, -1)),
() -> assertEquals(value, Preferences.getLong(key, -1)),
() -> assertEquals(value, m_table.getEntry(key).getNumber(-1).longValue()));
}
@@ -143,10 +142,10 @@ class PreferencesTest {
final String key = "test";
final float value = 9.42f;
m_prefs.putFloat(key, value);
Preferences.setFloat(key, value);
assertAll(
() -> assertEquals(value, m_prefs.getFloat(key, -1), 1e-6),
() -> assertEquals(value, Preferences.getFloat(key, -1), 1e-6),
() -> assertEquals(value, m_table.getEntry(key).getNumber(-1).floatValue(), 1e-6));
}
@@ -155,10 +154,10 @@ class PreferencesTest {
final String key = "test";
final double value = 6.28;
m_prefs.putDouble(key, value);
Preferences.setDouble(key, value);
assertAll(
() -> assertEquals(value, m_prefs.getDouble(key, -1), 1e-6),
() -> assertEquals(value, Preferences.getDouble(key, -1), 1e-6),
() -> assertEquals(value, m_table.getEntry(key).getNumber(-1).doubleValue(), 1e-6));
}
@@ -167,10 +166,10 @@ class PreferencesTest {
final String key = "test";
final String value = "value";
m_prefs.putString(key, value);
Preferences.setString(key, value);
assertAll(
() -> assertEquals(value, m_prefs.getString(key, "")),
() -> assertEquals(value, Preferences.getString(key, "")),
() -> assertEquals(value, m_table.getEntry(key).getString("")));
}
@@ -179,10 +178,10 @@ class PreferencesTest {
final String key = "test";
final boolean value = true;
m_prefs.putBoolean(key, value);
Preferences.setBoolean(key, value);
assertAll(
() -> assertEquals(value, m_prefs.getBoolean(key, false)),
() -> assertEquals(value, Preferences.getBoolean(key, false)),
() -> assertEquals(value, m_table.getEntry(key).getBoolean(false)));
}
}

View File

@@ -310,21 +310,6 @@ public final class TestBench {
return encoderPortPairs;
}
/**
* Gets the singleton of the TestBench. If the TestBench is not already allocated in constructs an
* new instance of it. Otherwise it returns the existing instance.
*
* @return The Singleton instance of the TestBench
* @deprecated Use the static methods instead
*/
@Deprecated
public static TestBench getInstance() {
if (instance == null) {
instance = new TestBench();
}
return instance;
}
/**
* Provides access to the output stream for the test system. This should be used instead of
* System.out This is gives us a way to implement changes to where the output text of this test

View File

@@ -1,80 +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.math;
import edu.wpi.first.math.numbers.N1;
import java.util.Objects;
import org.ejml.simple.SimpleMatrix;
@Deprecated
public final class MatrixUtils {
private MatrixUtils() {
throw new AssertionError("utility class");
}
/**
* Creates a new matrix of zeros.
*
* @param rows The number of rows in the matrix.
* @param cols The number of columns in the matrix.
* @param <R> The number of rows in the matrix as a generic.
* @param <C> The number of columns in the matrix as a generic.
* @return An RxC matrix filled with zeros.
*/
@SuppressWarnings("LineLength")
public static <R extends Num, C extends Num> Matrix<R, C> zeros(Nat<R> rows, Nat<C> cols) {
return new Matrix<>(
new SimpleMatrix(
Objects.requireNonNull(rows).getNum(), Objects.requireNonNull(cols).getNum()));
}
/**
* Creates a new vector of zeros.
*
* @param nums The size of the desired vector.
* @param <N> The size of the desired vector as a generic.
* @return A vector of size N filled with zeros.
*/
public static <N extends Num> Matrix<N, N1> zeros(Nat<N> nums) {
return new Matrix<>(new SimpleMatrix(Objects.requireNonNull(nums).getNum(), 1));
}
/**
* Creates the identity matrix of the given dimension.
*
* @param dim The dimension of the desired matrix.
* @param <D> The dimension of the desired matrix as a generic.
* @return The DxD identity matrix.
*/
public static <D extends Num> Matrix<D, D> eye(Nat<D> dim) {
return new Matrix<>(SimpleMatrix.identity(Objects.requireNonNull(dim).getNum()));
}
/**
* Entrypoint to the MatBuilder class for creation of custom matrices with the given dimensions
* and contents.
*
* @param rows The number of rows of the desired matrix.
* @param cols The number of columns of the desired matrix.
* @param <R> The number of rows of the desired matrix as a generic.
* @param <C> The number of columns of the desired matrix as a generic.
* @return A builder to construct the matrix.
*/
public static <R extends Num, C extends Num> MatBuilder<R, C> mat(Nat<R> rows, Nat<C> cols) {
return new MatBuilder<>(rows, cols);
}
/**
* Entrypoint to the VecBuilder class for creation of custom vectors with the given size and
* contents.
*
* @param dim The dimension of the vector.
* @param <D> The dimension of the vector as a generic.
* @return A builder to construct the vector.
*/
public static <D extends Num> VecBuilder<D> vec(Nat<D> dim) {
return new VecBuilder<>(dim);
}
}

View File

@@ -24,10 +24,6 @@ static decltype(1 / 1_rad) Sinc(units::radian_t x) {
}
}
RamseteController::RamseteController(double b, double zeta)
: RamseteController(units::unit_t<b_unit>{b},
units::unit_t<zeta_unit>{zeta}) {}
RamseteController::RamseteController(units::unit_t<b_unit> b,
units::unit_t<zeta_unit> zeta)
: m_b{b}, m_zeta{zeta} {}

View File

@@ -5,7 +5,6 @@
#pragma once
#include <wpi/SymbolExports.h>
#include <wpi/deprecated.h>
#include "frc/geometry/Pose2d.h"
#include "frc/kinematics/ChassisSpeeds.h"
@@ -50,17 +49,6 @@ class WPILIB_DLLEXPORT RamseteController {
units::inverse<units::squared<units::meters>>>;
using zeta_unit = units::inverse<units::radians>;
/**
* Construct a Ramsete unicycle controller.
*
* @param b Tuning parameter (b > 0 rad²/m²) for which larger values make
* convergence more aggressive like a proportional term.
* @param zeta Tuning parameter (0 rad⁻¹ < zeta < 1 rad⁻¹) for which larger
* values provide more damping in response.
*/
WPI_DEPRECATED("Use unit-safe constructor instead")
RamseteController(double b, double zeta);
/**
* Construct a Ramsete unicycle controller.
*

View File

@@ -4,11 +4,6 @@
#pragma once
#include <memory>
#include <string>
#include <string_view>
#include "wpi/deprecated.h"
#include "wpi/sendable/SendableRegistry.h"
namespace wpi {
@@ -48,123 +43,6 @@ class SendableHelper {
return *this;
}
/**
* Gets the name of this Sendable object.
*
* @deprecated use SendableRegistry::GetName()
*
* @return Name
*/
WPI_DEPRECATED("use SendableRegistry::GetName()")
std::string GetName() const {
return SendableRegistry::GetName(static_cast<const Derived*>(this));
}
/**
* Sets the name of this Sendable object.
*
* @deprecated use SendableRegistry::SetName()
*
* @param name name
*/
WPI_DEPRECATED("use SendableRegistry::SetName()")
void SetName(std::string_view name) {
SendableRegistry::SetName(static_cast<Derived*>(this), name);
}
/**
* Sets both the subsystem name and device name of this Sendable object.
*
* @deprecated use SendableRegistry::SetName()
*
* @param subsystem subsystem name
* @param name device name
*/
WPI_DEPRECATED("use SendableRegistry::SetName()")
void SetName(std::string_view subsystem, std::string_view name) {
SendableRegistry::SetName(static_cast<Derived*>(this), subsystem, name);
}
/**
* Gets the subsystem name of this Sendable object.
*
* @deprecated use SendableRegistry::GetSubsystem().
*
* @return Subsystem name
*/
WPI_DEPRECATED("use SendableRegistry::GetSubsystem()")
std::string GetSubsystem() const {
return SendableRegistry::GetSubsystem(static_cast<const Derived*>(this));
}
/**
* Sets the subsystem name of this Sendable object.
*
* @deprecated use SendableRegistry::SetSubsystem()
*
* @param subsystem subsystem name
*/
WPI_DEPRECATED("use SendableRegistry::SetSubsystem()")
void SetSubsystem(std::string_view subsystem) {
SendableRegistry::SetSubsystem(static_cast<Derived*>(this), subsystem);
}
protected:
/**
* Add a child component.
*
* @deprecated use SendableRegistry::AddChild()
*
* @param child child component
*/
WPI_DEPRECATED("use SendableRegistry::AddChild()")
void AddChild(std::shared_ptr<Sendable> child) {
SendableRegistry::AddChild(static_cast<Derived*>(this), child.get());
}
/**
* Add a child component.
*
* @deprecated use SendableRegistry::AddChild()
*
* @param child child component
*/
WPI_DEPRECATED("use SendableRegistry::AddChild()")
void AddChild(void* child) {
SendableRegistry::AddChild(static_cast<Derived*>(this), child);
}
/**
* Sets the name of the sensor with a channel number.
*
* @deprecated use SendableRegistry::SetName()
*
* @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(std::string_view moduleType, int channel) {
SendableRegistry::SetName(static_cast<Derived*>(this), moduleType, channel);
}
/**
* Sets the name of the sensor with a module and channel number.
*
* @deprecated use SendableRegistry::SetName()
*
* @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(std::string_view moduleType, int moduleNumber, int channel) {
SendableRegistry::SetName(static_cast<Derived*>(this), moduleType,
moduleNumber, channel);
}
protected:
SendableHelper() = default;