49template <
size_t NumModules>
51 :
public CommandHelper<Command, SwerveControllerCommand<NumModules>> {
52 using voltsecondspermeter =
55 using voltsecondssquaredpermeter =
92 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
130 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
160 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
192 std::function<
void(std::array<frc::SwerveModuleState, NumModules>)>
200 void End(
bool interrupted)
override;
209 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
215 units::second_t m_prevTime;
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:27
Represents requirements for a command, which is a set of (pointers to) subsystems.
Definition: Requirements.h:20
A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDCon...
Definition: SwerveControllerCommand.h:51
SwerveControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, 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, Requirements requirements={})
Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.
Definition: SwerveControllerCommand.inc:16
void End(bool interrupted) override
Definition: SwerveControllerCommand.inc:105
void Execute() override
Definition: SwerveControllerCommand.inc:92
void Initialize() override
Definition: SwerveControllerCommand.inc:82
bool IsFinished() override
Definition: SwerveControllerCommand.inc:110
This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain (i....
Definition: HolonomicDriveController.h:32
Implements a PID control loop.
Definition: PIDController.h:23
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
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:23
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:25
typename units::detail::inverse_impl< U >::type inverse
represents the inverse unit type of class U.
Definition: base.h:1134
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition: base.h:1434
Definition: TrapezoidProfileSubsystem.h:12
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13