mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
[wpimath] Move PIDController from frc2 to frc namespace (#5640)
The old PIDController class in the frc namespace was removed for the 2023 season.
This commit is contained in:
@@ -89,16 +89,16 @@ class MecanumControllerCommand
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SimpleMotorFeedforward<units::meters> feedforward,
|
||||
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
|
||||
frc2::PIDController yController,
|
||||
frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
|
||||
frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
units::meters_per_second_t maxWheelVelocity,
|
||||
std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
|
||||
frc2::PIDController frontLeftController,
|
||||
frc2::PIDController rearLeftController,
|
||||
frc2::PIDController frontRightController,
|
||||
frc2::PIDController rearRightController,
|
||||
frc::PIDController frontLeftController,
|
||||
frc::PIDController rearLeftController,
|
||||
frc::PIDController frontRightController,
|
||||
frc::PIDController rearRightController,
|
||||
std::function<void(units::volt_t, units::volt_t, units::volt_t,
|
||||
units::volt_t)>
|
||||
output,
|
||||
@@ -143,15 +143,15 @@ class MecanumControllerCommand
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SimpleMotorFeedforward<units::meters> feedforward,
|
||||
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
|
||||
frc2::PIDController yController,
|
||||
frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
|
||||
frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
units::meters_per_second_t maxWheelVelocity,
|
||||
std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
|
||||
frc2::PIDController frontLeftController,
|
||||
frc2::PIDController rearLeftController,
|
||||
frc2::PIDController frontRightController,
|
||||
frc2::PIDController rearRightController,
|
||||
frc::PIDController frontLeftController,
|
||||
frc::PIDController rearLeftController,
|
||||
frc::PIDController frontRightController,
|
||||
frc::PIDController rearRightController,
|
||||
std::function<void(units::volt_t, units::volt_t, units::volt_t,
|
||||
units::volt_t)>
|
||||
output,
|
||||
@@ -193,16 +193,16 @@ class MecanumControllerCommand
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SimpleMotorFeedforward<units::meters> feedforward,
|
||||
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
|
||||
frc2::PIDController yController,
|
||||
frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
|
||||
frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
units::meters_per_second_t maxWheelVelocity,
|
||||
std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
|
||||
frc2::PIDController frontLeftController,
|
||||
frc2::PIDController rearLeftController,
|
||||
frc2::PIDController frontRightController,
|
||||
frc2::PIDController rearRightController,
|
||||
frc::PIDController frontLeftController,
|
||||
frc::PIDController rearLeftController,
|
||||
frc::PIDController frontRightController,
|
||||
frc::PIDController rearRightController,
|
||||
std::function<void(units::volt_t, units::volt_t, units::volt_t,
|
||||
units::volt_t)>
|
||||
output,
|
||||
@@ -247,15 +247,15 @@ class MecanumControllerCommand
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SimpleMotorFeedforward<units::meters> feedforward,
|
||||
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
|
||||
frc2::PIDController yController,
|
||||
frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
|
||||
frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
units::meters_per_second_t maxWheelVelocity,
|
||||
std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
|
||||
frc2::PIDController frontLeftController,
|
||||
frc2::PIDController rearLeftController,
|
||||
frc2::PIDController frontRightController,
|
||||
frc2::PIDController rearRightController,
|
||||
frc::PIDController frontLeftController,
|
||||
frc::PIDController rearLeftController,
|
||||
frc::PIDController frontRightController,
|
||||
frc::PIDController rearRightController,
|
||||
std::function<void(units::volt_t, units::volt_t, units::volt_t,
|
||||
units::volt_t)>
|
||||
output,
|
||||
@@ -288,8 +288,8 @@ class MecanumControllerCommand
|
||||
*/
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
|
||||
frc2::PIDController yController,
|
||||
frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
|
||||
frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
units::meters_per_second_t maxWheelVelocity,
|
||||
@@ -329,8 +329,8 @@ class MecanumControllerCommand
|
||||
*/
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
|
||||
frc2::PIDController yController,
|
||||
frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
|
||||
frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
units::meters_per_second_t maxWheelVelocity,
|
||||
std::function<void(units::meters_per_second_t, units::meters_per_second_t,
|
||||
@@ -366,8 +366,8 @@ class MecanumControllerCommand
|
||||
*/
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
|
||||
frc2::PIDController yController,
|
||||
frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
|
||||
frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
units::meters_per_second_t maxWheelVelocity,
|
||||
@@ -407,8 +407,8 @@ class MecanumControllerCommand
|
||||
*/
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
|
||||
frc2::PIDController yController,
|
||||
frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
|
||||
frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
units::meters_per_second_t maxWheelVelocity,
|
||||
std::function<void(units::meters_per_second_t, units::meters_per_second_t,
|
||||
@@ -433,10 +433,10 @@ class MecanumControllerCommand
|
||||
frc::HolonomicDriveController m_controller;
|
||||
std::function<frc::Rotation2d()> m_desiredRotation;
|
||||
const units::meters_per_second_t m_maxWheelVelocity;
|
||||
std::unique_ptr<frc2::PIDController> m_frontLeftController;
|
||||
std::unique_ptr<frc2::PIDController> m_rearLeftController;
|
||||
std::unique_ptr<frc2::PIDController> m_frontRightController;
|
||||
std::unique_ptr<frc2::PIDController> m_rearRightController;
|
||||
std::unique_ptr<frc::PIDController> m_frontLeftController;
|
||||
std::unique_ptr<frc::PIDController> m_rearLeftController;
|
||||
std::unique_ptr<frc::PIDController> m_frontRightController;
|
||||
std::unique_ptr<frc::PIDController> m_rearRightController;
|
||||
std::function<frc::MecanumDriveWheelSpeeds()> m_currentWheelSpeeds;
|
||||
std::function<void(units::meters_per_second_t, units::meters_per_second_t,
|
||||
units::meters_per_second_t, units::meters_per_second_t)>
|
||||
|
||||
@@ -36,7 +36,7 @@ class PIDCommand : public CommandHelper<Command, PIDCommand> {
|
||||
* @param useOutput the controller's output
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
PIDCommand(PIDController controller,
|
||||
PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource,
|
||||
std::function<double()> setpointSource,
|
||||
std::function<void(double)> useOutput,
|
||||
@@ -52,7 +52,7 @@ class PIDCommand : public CommandHelper<Command, PIDCommand> {
|
||||
* @param useOutput the controller's output
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
PIDCommand(PIDController controller,
|
||||
PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource,
|
||||
std::function<double()> setpointSource,
|
||||
std::function<void(double)> useOutput,
|
||||
@@ -68,7 +68,7 @@ class PIDCommand : public CommandHelper<Command, PIDCommand> {
|
||||
* @param useOutput the controller's output
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
PIDCommand(PIDController controller,
|
||||
PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource, double setpoint,
|
||||
std::function<void(double)> useOutput,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
@@ -83,7 +83,7 @@ class PIDCommand : public CommandHelper<Command, PIDCommand> {
|
||||
* @param useOutput the controller's output
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
PIDCommand(PIDController controller,
|
||||
PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource, double setpoint,
|
||||
std::function<void(double)> useOutput,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
@@ -103,10 +103,10 @@ class PIDCommand : public CommandHelper<Command, PIDCommand> {
|
||||
*
|
||||
* @return The PIDController
|
||||
*/
|
||||
PIDController& GetController();
|
||||
frc::PIDController& GetController();
|
||||
|
||||
protected:
|
||||
PIDController m_controller;
|
||||
frc::PIDController m_controller;
|
||||
std::function<double()> m_measurement;
|
||||
std::function<double()> m_setpoint;
|
||||
std::function<void(double)> m_useOutput;
|
||||
|
||||
@@ -25,7 +25,8 @@ class PIDSubsystem : public SubsystemBase {
|
||||
* @param controller the PIDController to use
|
||||
* @param initialPosition the initial setpoint of the subsystem
|
||||
*/
|
||||
explicit PIDSubsystem(PIDController controller, double initialPosition = 0);
|
||||
explicit PIDSubsystem(frc::PIDController controller,
|
||||
double initialPosition = 0);
|
||||
|
||||
void Periodic() override;
|
||||
|
||||
@@ -65,10 +66,10 @@ class PIDSubsystem : public SubsystemBase {
|
||||
*
|
||||
* @return The controller.
|
||||
*/
|
||||
PIDController& GetController();
|
||||
frc::PIDController& GetController();
|
||||
|
||||
protected:
|
||||
PIDController m_controller;
|
||||
frc::PIDController m_controller;
|
||||
bool m_enabled{false};
|
||||
|
||||
/**
|
||||
|
||||
@@ -76,8 +76,8 @@ class RamseteCommand : public CommandHelper<Command, RamseteCommand> {
|
||||
frc::SimpleMotorFeedforward<units::meters> feedforward,
|
||||
frc::DifferentialDriveKinematics kinematics,
|
||||
std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
|
||||
frc2::PIDController leftController,
|
||||
frc2::PIDController rightController,
|
||||
frc::PIDController leftController,
|
||||
frc::PIDController rightController,
|
||||
std::function<void(units::volt_t, units::volt_t)> output,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
@@ -113,8 +113,8 @@ class RamseteCommand : public CommandHelper<Command, RamseteCommand> {
|
||||
frc::SimpleMotorFeedforward<units::meters> feedforward,
|
||||
frc::DifferentialDriveKinematics kinematics,
|
||||
std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
|
||||
frc2::PIDController leftController,
|
||||
frc2::PIDController rightController,
|
||||
frc::PIDController leftController,
|
||||
frc::PIDController rightController,
|
||||
std::function<void(units::volt_t, units::volt_t)> output,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
|
||||
@@ -183,8 +183,8 @@ class RamseteCommand : public CommandHelper<Command, RamseteCommand> {
|
||||
frc::SimpleMotorFeedforward<units::meters> m_feedforward;
|
||||
frc::DifferentialDriveKinematics m_kinematics;
|
||||
std::function<frc::DifferentialDriveWheelSpeeds()> m_speeds;
|
||||
std::unique_ptr<frc2::PIDController> m_leftController;
|
||||
std::unique_ptr<frc2::PIDController> m_rightController;
|
||||
std::unique_ptr<frc::PIDController> m_leftController;
|
||||
std::unique_ptr<frc::PIDController> m_rightController;
|
||||
std::function<void(units::volt_t, units::volt_t)> m_outputVolts;
|
||||
std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
|
||||
m_outputVel;
|
||||
|
||||
@@ -89,7 +89,7 @@ class SwerveControllerCommand
|
||||
SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc2::PIDController xController, frc2::PIDController yController,
|
||||
frc::PIDController xController, frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
|
||||
@@ -128,7 +128,7 @@ class SwerveControllerCommand
|
||||
SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc2::PIDController xController, frc2::PIDController yController,
|
||||
frc::PIDController xController, frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
|
||||
output,
|
||||
@@ -164,7 +164,7 @@ class SwerveControllerCommand
|
||||
SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc2::PIDController xController, frc2::PIDController yController,
|
||||
frc::PIDController xController, frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
|
||||
@@ -203,7 +203,7 @@ class SwerveControllerCommand
|
||||
SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc2::PIDController xController, frc2::PIDController yController,
|
||||
frc::PIDController xController, frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
|
||||
output,
|
||||
|
||||
@@ -16,7 +16,7 @@ template <size_t NumModules>
|
||||
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc2::PIDController xController, frc2::PIDController yController,
|
||||
frc::PIDController xController, frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
@@ -34,7 +34,7 @@ template <size_t NumModules>
|
||||
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc2::PIDController xController, frc2::PIDController yController,
|
||||
frc::PIDController xController, frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
@@ -50,7 +50,7 @@ template <size_t NumModules>
|
||||
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc2::PIDController xController, frc2::PIDController yController,
|
||||
frc::PIDController xController, frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
@@ -68,7 +68,7 @@ template <size_t NumModules>
|
||||
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc2::PIDController xController, frc2::PIDController yController,
|
||||
frc::PIDController xController, frc::PIDController yController,
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
std::span<Subsystem* const> requirements)
|
||||
|
||||
Reference in New Issue
Block a user