Skip to content

Commit

Permalink
[cmd] Deprecate control commands and subsystems
Browse files Browse the repository at this point in the history
  • Loading branch information
Gold856 committed Oct 11, 2024
1 parent 8f57e4c commit b28aeee
Show file tree
Hide file tree
Showing 12 changed files with 35 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,10 @@
* are performed synchronously in the command's execute() method.
*
* <p>This class is provided by the NewCommands VendorDep
*
* @deprecated Use a PIDController instead
*/
@Deprecated(forRemoval = true, since = "2025")
public class PIDCommand extends Command {
/** PID controller. */
protected final PIDController m_controller;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,10 @@
* synchronously from the subsystem's periodic() method.
*
* <p>This class is provided by the NewCommands VendorDep
*
* @deprecated Use a PIDController instead
*/
@Deprecated(forRemoval = true, since = "2025")
public abstract class PIDSubsystem extends SubsystemBase {
/** PID controller. */
protected final PIDController m_controller;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,10 @@
* output are performed synchronously in the command's execute() method.
*
* <p>This class is provided by the NewCommands VendorDep
*
* @deprecated Use a ProfiledPIDController instead
*/
@Deprecated(forRemoval = true, since = "2025")
public class ProfiledPIDCommand extends Command {
/** Profiled PID controller. */
protected final ProfiledPIDController m_controller;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,17 @@

import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.trajectory.TrapezoidProfile.State;

/**
* A subsystem that uses a {@link ProfiledPIDController} to control an output. The controller is run
* synchronously from the subsystem's periodic() method.
*
* <p>This class is provided by the NewCommands VendorDep
*
* @deprecated Use a ProfiledPIDController instead
*/
@Deprecated(forRemoval = true, since = "2025")
public abstract class ProfiledPIDSubsystem extends SubsystemBase {
/** Profiled PID controller. */
protected final ProfiledPIDController m_controller;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,19 @@

package edu.wpi.first.wpilibj2.command;

import static edu.wpi.first.math.trajectory.TrapezoidProfile.State;
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;

import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.trajectory.TrapezoidProfile.State;
import java.util.function.Consumer;
import java.util.function.Supplier;

/**
* A command that runs a {@link TrapezoidProfile}. Useful for smoothly controlling mechanism motion.
*
* <p>This class is provided by the NewCommands VendorDep
*
* @deprecated Use a TrapezoidProfile instead
*/
@Deprecated(since = "2025", forRemoval = true)
public class TrapezoidProfileCommand extends Command {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,10 @@
* how to use the current state of the motion profile by overriding the `useState` method.
*
* <p>This class is provided by the NewCommands VendorDep
*
* @deprecated Use a TrapezoidProfile instead
*/
@Deprecated(forRemoval = true, since = "2025")
public abstract class TrapezoidProfileSubsystem extends SubsystemBase {
private final double m_period;
private final TrapezoidProfile m_profile;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,10 @@ namespace frc2 {
* This class is provided by the NewCommands VendorDep
*
* @see PIDController
* @deprecated Use a PIDController instead
*/
class PIDCommand : public CommandHelper<Command, PIDCommand> {
class [[deprecated("Use a PIDController instead")]] PIDCommand
: public CommandHelper<Command, PIDCommand> {
public:
/**
* Creates a new PIDCommand, which controls the given output with a
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,10 @@ namespace frc2 {
* This class is provided by the NewCommands VendorDep
*
* @see PIDController
* @deprecated Use a PIDController instead
*/
class PIDSubsystem : public SubsystemBase {
class [[deprecated("Use a PIDController instead")]] PIDSubsystem
: public SubsystemBase {
public:
/**
* Creates a new PIDSubsystem.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,10 @@ namespace frc2 {
* This class is provided by the NewCommands VendorDep
*
* @see ProfiledPIDController<Distance>
* @deprecated Use a ProfiledPIDController instead
*/
template <class Distance>
class ProfiledPIDCommand
class [[deprecated("Use a ProfiledPIDController instead")]] ProfiledPIDCommand
: public CommandHelper<Command, ProfiledPIDCommand<Distance>> {
using Distance_t = units::unit_t<Distance>;
using Velocity =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,11 @@ namespace frc2 {
* This class is provided by the NewCommands VendorDep
*
* @see ProfiledPIDController
* @deprecated Use a ProfiledPIDController instead
*/
template <class Distance>
class ProfiledPIDSubsystem : public SubsystemBase {
class [[deprecated("Use a ProfiledPIDController instead")]] ProfiledPIDSubsystem
: public SubsystemBase {
using Distance_t = units::unit_t<Distance>;
using Velocity =
units::compound_unit<Distance, units::inverse<units::seconds>>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,10 @@ namespace frc2 {
* This class is provided by the NewCommands VendorDep
*
* @see TrapezoidProfile
* @deprecated Use a TrapezoidProfile instead
*/
template <class Distance>
class TrapezoidProfileCommand
class [[deprecated("Use a TrapezoidProfile instead")]] TrapezoidProfileCommand
: public CommandHelper<Command, TrapezoidProfileCommand<Distance>> {
using Distance_t = units::unit_t<Distance>;
using Velocity =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,11 @@ namespace frc2 {
* profile by overriding the `UseState` method.
*
* This class is provided by the NewCommands VendorDep
* @deprecated Use a TrapezoidProfile instead
*/
template <class Distance>
class TrapezoidProfileSubsystem : public SubsystemBase {
class [[deprecated("Use a TrapezoidProfile instead")]] TrapezoidProfileSubsystem
: public SubsystemBase {
using Distance_t = units::unit_t<Distance>;
using Velocity =
units::compound_unit<Distance, units::inverse<units::seconds>>;
Expand Down

0 comments on commit b28aeee

Please sign in to comment.