7#include <initializer_list>
54 :
public CommandHelper<CommandBase, MecanumControllerCommand> {
96 units::meters_per_second_t maxWheelVelocity,
102 std::function<
void(units::volt_t, units::volt_t, units::volt_t,
105 std::initializer_list<Subsystem*> requirements);
149 units::meters_per_second_t maxWheelVelocity,
155 std::function<
void(units::volt_t, units::volt_t, units::volt_t,
158 std::initializer_list<Subsystem*> requirements);
200 units::meters_per_second_t maxWheelVelocity,
206 std::function<
void(units::volt_t, units::volt_t, units::volt_t,
209 std::span<Subsystem* const> requirements = {});
253 units::meters_per_second_t maxWheelVelocity,
259 std::function<
void(units::volt_t, units::volt_t, units::volt_t,
262 std::span<Subsystem* const> requirements = {});
295 units::meters_per_second_t maxWheelVelocity,
296 std::function<
void(units::meters_per_second_t, units::meters_per_second_t,
297 units::meters_per_second_t,
298 units::meters_per_second_t)>
300 std::initializer_list<Subsystem*> requirements);
335 units::meters_per_second_t maxWheelVelocity,
336 std::function<
void(units::meters_per_second_t, units::meters_per_second_t,
337 units::meters_per_second_t,
338 units::meters_per_second_t)>
340 std::initializer_list<Subsystem*> requirements);
373 units::meters_per_second_t maxWheelVelocity,
374 std::function<
void(units::meters_per_second_t, units::meters_per_second_t,
375 units::meters_per_second_t,
376 units::meters_per_second_t)>
378 std::span<Subsystem* const> requirements = {});
413 units::meters_per_second_t maxWheelVelocity,
414 std::function<
void(units::meters_per_second_t, units::meters_per_second_t,
415 units::meters_per_second_t,
416 units::meters_per_second_t)>
418 std::span<Subsystem* const> requirements = {});
424 void End(
bool interrupted)
override;
435 const units::meters_per_second_t m_maxWheelVelocity;
436 std::unique_ptr<frc2::PIDController> m_frontLeftController;
437 std::unique_ptr<frc2::PIDController> m_rearLeftController;
438 std::unique_ptr<frc2::PIDController> m_frontRightController;
439 std::unique_ptr<frc2::PIDController> m_rearRightController;
441 std::function<void(units::meters_per_second_t, units::meters_per_second_t,
442 units::meters_per_second_t, units::meters_per_second_t)>
444 std::function<void(units::volt_t, units::volt_t, units::volt_t,
451 units::second_t m_prevTime;
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:25
A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDCon...
Definition: MecanumControllerCommand.h:54
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::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, units::meters_per_second_t, units::meters_per_second_t)> output, std::span< Subsystem *const > requirements={})
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::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, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::span< Subsystem *const > requirements={})
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::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, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::span< Subsystem *const > requirements={})
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> output, std::span< Subsystem *const > requirements={})
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
bool IsFinished() override
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::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, units::meters_per_second_t, units::meters_per_second_t)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::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, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::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, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
void Initialize() override
void End(bool interrupted) override
Implements a PID control loop.
Definition: PIDController.h:23
This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain (i....
Definition: HolonomicDriveController.h:32
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition: MecanumDriveKinematics.h:44
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
A timer class.
Definition: Timer.h:36
Represents a time-parameterized trajectory.
Definition: Trajectory.h:28
Definition: ProfiledPIDCommand.h:18
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13
Represents the wheel speeds for a mecanum drive drivetrain.
Definition: MecanumDriveWheelSpeeds.h:15