7#include <initializer_list>
52template <
size_t NumModules>
54 :
public CommandHelper<CommandBase, SwerveControllerCommand<NumModules>> {
55 using voltsecondspermeter =
58 using voltsecondssquaredpermeter =
95 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
97 std::initializer_list<Subsystem*> requirements);
133 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
135 std::initializer_list<Subsystem*> requirements);
170 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
172 std::span<Subsystem* const> requirements = {});
208 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
210 std::span<Subsystem* const> requirements = {});
238 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
240 std::initializer_list<Subsystem*> requirements);
270 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
272 std::initializer_list<Subsystem*> requirements);
301 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
303 std::span<Subsystem* const> requirements = {});
333 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
335 std::span<Subsystem* const> requirements = {});
341 void End(
bool interrupted)
override;
350 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
356 units::second_t m_prevTime;
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:25
Implements a PID control loop.
Definition: PIDController.h:23
A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDCon...
Definition: SwerveControllerCommand.h:54
void End(bool interrupted) override
Definition: SwerveControllerCommand.inc:170
void Execute() override
Definition: SwerveControllerCommand.inc:157
void Initialize() override
Definition: SwerveControllerCommand.inc:147
SwerveControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.
Definition: SwerveControllerCommand.inc:15
bool IsFinished() override
Definition: SwerveControllerCommand.inc:175
This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain (i....
Definition: HolonomicDriveController.h:32
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
Implements a PID control loop whose setpoint is constrained by a trapezoid profile.
Definition: ProfiledPIDController.h:35
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition: SwerveDriveKinematics.h:56
A timer class.
Definition: Timer.h:36
Represents a time-parameterized trajectory.
Definition: Trajectory.h:28
typename units::detail::inverse_impl< U >::type inverse
represents the inverse unit type of class U.
Definition: base.h:1145
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition: base.h:1445
Definition: ProfiledPIDCommand.h:18
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13