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:
@@ -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