mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[commands] Add C++ Requirements struct (#5504)
This commit is contained in:
@@ -15,6 +15,7 @@
|
||||
#include <wpi/SmallSet.h>
|
||||
#include <wpi/sendable/Sendable.h>
|
||||
|
||||
#include "frc2/command/Requirements.h"
|
||||
#include "frc2/command/Subsystem.h"
|
||||
|
||||
namespace frc2 {
|
||||
@@ -104,23 +105,15 @@ class Command : public wpi::Sendable, public wpi::SendableHelper<Command> {
|
||||
* is scheduled, so this method should normally be called from the command's
|
||||
* constructor.
|
||||
*
|
||||
* @param requirements the Subsystem requirements to add
|
||||
* While this overload can be used with {@code AddRequirements({&subsystem1,
|
||||
* &subsystem2})}, {@code AddRequirements({&subsystem})} selects the {@code
|
||||
* AddRequirements(Subsystem*)} overload, which will function identically but
|
||||
* may cause warnings about redundant braces.
|
||||
*
|
||||
* @param requirements the Subsystem requirements to add, which can be
|
||||
* implicitly constructed from an initializer list or a span
|
||||
*/
|
||||
void AddRequirements(std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Adds the specified Subsystem requirements to the command.
|
||||
*
|
||||
* The scheduler will prevent two commands that require the same subsystem
|
||||
* from being scheduled simultaneously.
|
||||
*
|
||||
* Note that the scheduler determines the requirements of a command when it
|
||||
* is scheduled, so this method should normally be called from the command's
|
||||
* constructor.
|
||||
*
|
||||
* @param requirements the Subsystem requirements to add
|
||||
*/
|
||||
void AddRequirements(std::span<Subsystem* const> requirements);
|
||||
void AddRequirements(Requirements requirements);
|
||||
|
||||
/**
|
||||
* Adds the specified Subsystem requirements to the command.
|
||||
@@ -238,18 +231,7 @@ class Command : public wpi::Sendable, public wpi::SendableHelper<Command> {
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr BeforeStarting(std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command with a runnable to run before this command starts.
|
||||
*
|
||||
* @param toRun the Runnable to run
|
||||
* @param requirements the required subsystems
|
||||
* @return the decorated command
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr BeforeStarting(std::function<void()> toRun,
|
||||
std::span<Subsystem* const> requirements = {}) &&;
|
||||
Requirements requirements = {}) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command with a runnable to run after the command finishes.
|
||||
@@ -260,18 +242,7 @@ class Command : public wpi::Sendable, public wpi::SendableHelper<Command> {
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr AndThen(std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command with a runnable to run after the command finishes.
|
||||
*
|
||||
* @param toRun the Runnable to run
|
||||
* @param requirements the required subsystems
|
||||
* @return the decorated command
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr AndThen(std::function<void()> toRun,
|
||||
std::span<Subsystem* const> requirements = {}) &&;
|
||||
Requirements requirements = {}) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command to run repeatedly, restarting it when it ends, until
|
||||
|
||||
@@ -88,18 +88,7 @@ class CommandPtr final {
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr AndThen(std::function<void()> toRun,
|
||||
std::span<Subsystem* const> requirements = {}) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command with a runnable to run after the command finishes.
|
||||
*
|
||||
* @param toRun the Runnable to run
|
||||
* @param requirements the required subsystems
|
||||
* @return the decorated command
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr AndThen(std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements) &&;
|
||||
Requirements requirements = {}) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command with a set of commands to run after it in sequence.
|
||||
@@ -121,18 +110,7 @@ class CommandPtr final {
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr BeforeStarting(std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command with a runnable to run before this command starts.
|
||||
*
|
||||
* @param toRun the Runnable to run
|
||||
* @param requirements the required subsystems
|
||||
* @return the decorated command
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr BeforeStarting(std::function<void()> toRun,
|
||||
std::span<Subsystem* const> requirements = {}) &&;
|
||||
Requirements requirements = {}) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command with another command to run before this command
|
||||
|
||||
@@ -49,17 +49,7 @@ CommandPtr Idle();
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr RunOnce(std::function<void()> action,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Constructs a command that runs an action once and finishes.
|
||||
*
|
||||
* @param action the action to run
|
||||
* @param requirements subsystems the action requires
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr RunOnce(std::function<void()> action,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a command that runs an action every iteration until interrupted.
|
||||
@@ -68,18 +58,7 @@ CommandPtr RunOnce(std::function<void()> action,
|
||||
* @param requirements subsystems the action requires
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr Run(std::function<void()> action,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Constructs a command that runs an action every iteration until interrupted.
|
||||
*
|
||||
* @param action the action to run
|
||||
* @param requirements subsystems the action requires
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr Run(std::function<void()> action,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
CommandPtr Run(std::function<void()> action, Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a command that runs an action once and another action when the
|
||||
@@ -91,19 +70,7 @@ CommandPtr Run(std::function<void()> action,
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr StartEnd(std::function<void()> start, std::function<void()> end,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Constructs a command that runs an action once and another action when the
|
||||
* command is interrupted.
|
||||
*
|
||||
* @param start the action to run on start
|
||||
* @param end the action to run on interrupt
|
||||
* @param requirements subsystems the action requires
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr StartEnd(std::function<void()> start, std::function<void()> end,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a command that runs an action every iteration until interrupted,
|
||||
@@ -115,19 +82,7 @@ CommandPtr StartEnd(std::function<void()> start, std::function<void()> end,
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr RunEnd(std::function<void()> run, std::function<void()> end,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Constructs a command that runs an action every iteration until interrupted,
|
||||
* and then runs a second action.
|
||||
*
|
||||
* @param run the action to run every iteration
|
||||
* @param end the action to run on interrupt
|
||||
* @param requirements subsystems the action requires
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr RunEnd(std::function<void()> run, std::function<void()> end,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a command that prints a message and finishes.
|
||||
|
||||
@@ -37,23 +37,7 @@ class FunctionalCommand : public CommandHelper<Command, FunctionalCommand> {
|
||||
std::function<void()> onExecute,
|
||||
std::function<void(bool)> onEnd,
|
||||
std::function<bool()> isFinished,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Creates a new FunctionalCommand.
|
||||
*
|
||||
* @param onInit the function to run on command initialization
|
||||
* @param onExecute the function to run on command execution
|
||||
* @param onEnd the function to run on command end
|
||||
* @param isFinished the function that determines whether the command has
|
||||
* finished
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
FunctionalCommand(std::function<void()> onInit,
|
||||
std::function<void()> onExecute,
|
||||
std::function<void(bool)> onEnd,
|
||||
std::function<bool()> isFinished,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
FunctionalCommand(FunctionalCommand&& other) = default;
|
||||
|
||||
|
||||
@@ -21,16 +21,6 @@ namespace frc2 {
|
||||
*/
|
||||
class InstantCommand : public CommandHelper<FunctionalCommand, InstantCommand> {
|
||||
public:
|
||||
/**
|
||||
* Creates a new InstantCommand that runs the given Runnable with the given
|
||||
* requirements.
|
||||
*
|
||||
* @param toRun the Runnable to run
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
InstantCommand(std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Creates a new InstantCommand that runs the given Runnable with the given
|
||||
* requirements.
|
||||
@@ -39,7 +29,7 @@ class InstantCommand : public CommandHelper<FunctionalCommand, InstantCommand> {
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
explicit InstantCommand(std::function<void()> toRun,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
InstantCommand(InstantCommand&& other) = default;
|
||||
|
||||
|
||||
@@ -102,7 +102,7 @@ class MecanumControllerCommand
|
||||
std::function<void(units::volt_t, units::volt_t, units::volt_t,
|
||||
units::volt_t)>
|
||||
output,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a new MecanumControllerCommand that when executed will follow
|
||||
@@ -155,111 +155,7 @@ class MecanumControllerCommand
|
||||
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. PID control and feedforward are handled
|
||||
* internally. Outputs are scaled from -12 to 12 as a voltage output to the
|
||||
* motor.
|
||||
*
|
||||
* <p>Note: The controllers will *not* set the outputVolts to zero upon
|
||||
* completion of the path this is left to the user, since it is not
|
||||
* appropriate for paths with nonstationary endstates.
|
||||
*
|
||||
* @param trajectory The trajectory to follow.
|
||||
* @param pose A function that supplies the robot pose,
|
||||
* provided by the odometry class.
|
||||
* @param feedforward The feedforward to use for the drivetrain.
|
||||
* @param kinematics The kinematics for the robot drivetrain.
|
||||
* @param xController The Trajectory Tracker PID controller
|
||||
* for the robot's x position.
|
||||
* @param yController The Trajectory Tracker PID controller
|
||||
* for the robot's y position.
|
||||
* @param thetaController The Trajectory Tracker PID controller
|
||||
* for angle for the robot.
|
||||
* @param desiredRotation The angle that the robot should be facing.
|
||||
* This is sampled at each time step.
|
||||
* @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
|
||||
* @param frontLeftController The front left wheel velocity PID.
|
||||
* @param rearLeftController The rear left wheel velocity PID.
|
||||
* @param frontRightController The front right wheel velocity PID.
|
||||
* @param rearRightController The rear right wheel velocity PID.
|
||||
* @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing
|
||||
* the current wheel speeds.
|
||||
* @param output The output of the velocity PIDs.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SimpleMotorFeedforward<units::meters> feedforward,
|
||||
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,
|
||||
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,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a new MecanumControllerCommand that when executed will follow
|
||||
* the provided trajectory. PID control and feedforward are handled
|
||||
* internally. Outputs are scaled from -12 to 12 as a voltage output to the
|
||||
* motor.
|
||||
*
|
||||
* <p>Note: The controllers will *not* set the outputVolts to zero upon
|
||||
* completion of the path this is left to the user, since it is not
|
||||
* appropriate for paths with nonstationary endstates.
|
||||
*
|
||||
* <p>Note 2: The final rotation of the robot will be set to the rotation of
|
||||
* the final pose in the trajectory. The robot will not follow the rotations
|
||||
* from the poses at each timestep. If alternate rotation behavior is desired,
|
||||
* the other constructor with a supplier for rotation should be used.
|
||||
*
|
||||
* @param trajectory The trajectory to follow.
|
||||
* @param pose A function that supplies the robot pose,
|
||||
* provided by the odometry class.
|
||||
* @param feedforward The feedforward to use for the drivetrain.
|
||||
* @param kinematics The kinematics for the robot drivetrain.
|
||||
* @param xController The Trajectory Tracker PID controller
|
||||
* for the robot's x position.
|
||||
* @param yController The Trajectory Tracker PID controller
|
||||
* for the robot's y position.
|
||||
* @param thetaController The Trajectory Tracker PID controller
|
||||
* for angle for the robot.
|
||||
* @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
|
||||
* @param frontLeftController The front left wheel velocity PID.
|
||||
* @param rearLeftController The rear left wheel velocity PID.
|
||||
* @param frontRightController The front right wheel velocity PID.
|
||||
* @param rearRightController The rear right wheel velocity PID.
|
||||
* @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing
|
||||
* the current wheel speeds.
|
||||
* @param output The output of the velocity PIDs.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SimpleMotorFeedforward<units::meters> feedforward,
|
||||
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,
|
||||
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,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a new MecanumControllerCommand that when executed will follow
|
||||
@@ -297,7 +193,7 @@ class MecanumControllerCommand
|
||||
units::meters_per_second_t,
|
||||
units::meters_per_second_t)>
|
||||
output,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
Requirements requirements);
|
||||
|
||||
/**
|
||||
* Constructs a new MecanumControllerCommand that when executed will follow
|
||||
@@ -337,85 +233,7 @@ class MecanumControllerCommand
|
||||
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. The user should implement a velocity PID on the
|
||||
* desired output wheel velocities.
|
||||
*
|
||||
* <p>Note: The controllers will *not* set the outputVolts to zero upon
|
||||
* completion of the path - this is left to the user, since it is not
|
||||
* appropriate for paths with nonstationary end-states.
|
||||
*
|
||||
* @param trajectory The trajectory to follow.
|
||||
* @param pose A function that supplies the robot pose - use one
|
||||
* of the odometry classes to provide this.
|
||||
* @param kinematics The kinematics for the robot drivetrain.
|
||||
* @param xController The Trajectory Tracker PID controller
|
||||
* for the robot's x position.
|
||||
* @param yController The Trajectory Tracker PID controller
|
||||
* for the robot's y position.
|
||||
* @param thetaController The Trajectory Tracker PID controller
|
||||
* for angle for the robot.
|
||||
* @param desiredRotation The angle that the robot should be facing.
|
||||
* This is sampled at every time step.
|
||||
* @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
|
||||
* @param output The output of the position PIDs.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
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<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. The user should implement a velocity PID on the
|
||||
* desired output wheel velocities.
|
||||
*
|
||||
* <p>Note: The controllers will *not* set the outputVolts to zero upon
|
||||
* completion of the path - this is left to the user, since it is not
|
||||
* appropriate for paths with nonstationary end-states.
|
||||
*
|
||||
* <p>Note2: The final rotation of the robot will be set to the rotation of
|
||||
* the final pose in the trajectory. The robot will not follow the rotations
|
||||
* from the poses at each timestep. If alternate rotation behavior is desired,
|
||||
* the other constructor with a supplier for rotation should be used.
|
||||
*
|
||||
* @param trajectory The trajectory to follow.
|
||||
* @param pose A function that supplies the robot pose - use one
|
||||
* of the odometry classes to provide this.
|
||||
* @param kinematics The kinematics for the robot drivetrain.
|
||||
* @param xController The Trajectory Tracker PID controller
|
||||
* for the robot's x position.
|
||||
* @param yController The Trajectory Tracker PID controller
|
||||
* for the robot's y position.
|
||||
* @param thetaController The Trajectory Tracker PID controller
|
||||
* for angle for the robot.
|
||||
* @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
|
||||
* @param output The output of the position PIDs.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
MecanumControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
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,
|
||||
units::meters_per_second_t,
|
||||
units::meters_per_second_t)>
|
||||
output,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
void Initialize() override;
|
||||
|
||||
|
||||
@@ -37,17 +37,7 @@ class NotifierCommand : public CommandHelper<Command, NotifierCommand> {
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
NotifierCommand(std::function<void()> toRun, units::second_t period,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Creates a new NotifierCommand.
|
||||
*
|
||||
* @param toRun the runnable for the notifier to run
|
||||
* @param period the period at which the notifier should run
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
NotifierCommand(std::function<void()> toRun, units::second_t period,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
NotifierCommand(NotifierCommand&& other);
|
||||
|
||||
|
||||
@@ -40,23 +40,7 @@ class PIDCommand : public CommandHelper<Command, PIDCommand> {
|
||||
std::function<double()> measurementSource,
|
||||
std::function<double()> setpointSource,
|
||||
std::function<void(double)> useOutput,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Creates a new PIDCommand, which controls the given output with a
|
||||
* PIDController.
|
||||
*
|
||||
* @param controller the controller that controls the output.
|
||||
* @param measurementSource the measurement of the process variable
|
||||
* @param setpointSource the controller's reference (aka setpoint)
|
||||
* @param useOutput the controller's output
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource,
|
||||
std::function<double()> setpointSource,
|
||||
std::function<void(double)> useOutput,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Creates a new PIDCommand, which controls the given output with a
|
||||
@@ -71,22 +55,7 @@ class PIDCommand : public CommandHelper<Command, PIDCommand> {
|
||||
PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource, double setpoint,
|
||||
std::function<void(double)> useOutput,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Creates a new PIDCommand, which controls the given output with a
|
||||
* PIDController with a constant setpoint.
|
||||
*
|
||||
* @param controller the controller that controls the output.
|
||||
* @param measurementSource the measurement of the process variable
|
||||
* @param setpoint the controller's setpoint (aka setpoint)
|
||||
* @param useOutput the controller's output
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource, double setpoint,
|
||||
std::function<void(double)> useOutput,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
PIDCommand(PIDCommand&& other) = default;
|
||||
|
||||
|
||||
@@ -50,29 +50,7 @@ class ProfiledPIDCommand
|
||||
std::function<Distance_t()> measurementSource,
|
||||
std::function<State()> goalSource,
|
||||
std::function<void(double, State)> useOutput,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_controller{controller},
|
||||
m_measurement{std::move(measurementSource)},
|
||||
m_goal{std::move(goalSource)},
|
||||
m_useOutput{std::move(useOutput)} {
|
||||
this->AddRequirements(requirements);
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a new PIDCommand, which controls the given output with a
|
||||
* ProfiledPIDController.
|
||||
*
|
||||
* @param controller the controller that controls the output.
|
||||
* @param measurementSource the measurement of the process variable
|
||||
* @param goalSource the controller's goal
|
||||
* @param useOutput the controller's output
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
ProfiledPIDCommand(frc::ProfiledPIDController<Distance> controller,
|
||||
std::function<Distance_t()> measurementSource,
|
||||
std::function<State()> goalSource,
|
||||
std::function<void(double, State)> useOutput,
|
||||
std::span<Subsystem* const> requirements = {})
|
||||
Requirements requirements = {})
|
||||
: m_controller{controller},
|
||||
m_measurement{std::move(measurementSource)},
|
||||
m_goal{std::move(goalSource)},
|
||||
@@ -94,29 +72,7 @@ class ProfiledPIDCommand
|
||||
std::function<Distance_t()> measurementSource,
|
||||
std::function<Distance_t()> goalSource,
|
||||
std::function<void(double, State)> useOutput,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: ProfiledPIDCommand(
|
||||
controller, measurementSource,
|
||||
[goalSource = std::move(goalSource)]() {
|
||||
return State{goalSource(), Velocity_t{0}};
|
||||
},
|
||||
useOutput, requirements) {}
|
||||
|
||||
/**
|
||||
* Creates a new PIDCommand, which controls the given output with a
|
||||
* ProfiledPIDController.
|
||||
*
|
||||
* @param controller the controller that controls the output.
|
||||
* @param measurementSource the measurement of the process variable
|
||||
* @param goalSource the controller's goal
|
||||
* @param useOutput the controller's output
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
ProfiledPIDCommand(frc::ProfiledPIDController<Distance> controller,
|
||||
std::function<Distance_t()> measurementSource,
|
||||
std::function<Distance_t()> goalSource,
|
||||
std::function<void(double, State)> useOutput,
|
||||
std::span<Subsystem* const> requirements = {})
|
||||
Requirements requirements = {})
|
||||
: ProfiledPIDCommand(
|
||||
controller, measurementSource,
|
||||
[goalSource = std::move(goalSource)]() {
|
||||
@@ -137,25 +93,7 @@ class ProfiledPIDCommand
|
||||
ProfiledPIDCommand(frc::ProfiledPIDController<Distance> controller,
|
||||
std::function<Distance_t()> measurementSource, State goal,
|
||||
std::function<void(double, State)> useOutput,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: ProfiledPIDCommand(
|
||||
controller, measurementSource, [goal] { return goal; }, useOutput,
|
||||
requirements) {}
|
||||
|
||||
/**
|
||||
* Creates a new PIDCommand, which controls the given output with a
|
||||
* ProfiledPIDController with a constant goal.
|
||||
*
|
||||
* @param controller the controller that controls the output.
|
||||
* @param measurementSource the measurement of the process variable
|
||||
* @param goal the controller's goal
|
||||
* @param useOutput the controller's output
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
ProfiledPIDCommand(frc::ProfiledPIDController<Distance> controller,
|
||||
std::function<Distance_t()> measurementSource, State goal,
|
||||
std::function<void(double, State)> useOutput,
|
||||
std::span<Subsystem* const> requirements = {})
|
||||
Requirements requirements = {})
|
||||
: ProfiledPIDCommand(
|
||||
controller, measurementSource, [goal] { return goal; }, useOutput,
|
||||
requirements) {}
|
||||
@@ -174,26 +112,7 @@ class ProfiledPIDCommand
|
||||
std::function<Distance_t()> measurementSource,
|
||||
Distance_t goal,
|
||||
std::function<void(double, State)> useOutput,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: ProfiledPIDCommand(
|
||||
controller, measurementSource, [goal] { return goal; }, useOutput,
|
||||
requirements) {}
|
||||
|
||||
/**
|
||||
* Creates a new PIDCommand, which controls the given output with a
|
||||
* ProfiledPIDController with a constant goal.
|
||||
*
|
||||
* @param controller the controller that controls the output.
|
||||
* @param measurementSource the measurement of the process variable
|
||||
* @param goal the controller's goal
|
||||
* @param useOutput the controller's output
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
ProfiledPIDCommand(frc::ProfiledPIDController<Distance> controller,
|
||||
std::function<Distance_t()> measurementSource,
|
||||
Distance_t goal,
|
||||
std::function<void(double, State)> useOutput,
|
||||
std::span<Subsystem* const> requirements = {})
|
||||
Requirements requirements = {})
|
||||
: ProfiledPIDCommand(
|
||||
controller, measurementSource, [goal] { return goal; }, useOutput,
|
||||
requirements) {}
|
||||
|
||||
@@ -79,44 +79,7 @@ class RamseteCommand : public CommandHelper<Command, RamseteCommand> {
|
||||
frc::PIDController leftController,
|
||||
frc::PIDController rightController,
|
||||
std::function<void(units::volt_t, units::volt_t)> output,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Constructs a new RamseteCommand that, when executed, will follow the
|
||||
* provided trajectory. PID control and feedforward are handled internally,
|
||||
* and outputs are scaled -12 to 12 representing units of volts.
|
||||
*
|
||||
* <p>Note: The controller will *not* set the outputVolts to zero upon
|
||||
* completion of the path - this is left to the user, since it is not
|
||||
* appropriate for paths with nonstationary endstates.
|
||||
*
|
||||
* @param trajectory The trajectory to follow.
|
||||
* @param pose A function that supplies the robot pose - use one of
|
||||
* the odometry classes to provide this.
|
||||
* @param controller The RAMSETE controller used to follow the
|
||||
* trajectory.
|
||||
* @param feedforward A component for calculating the feedforward for the
|
||||
* drive.
|
||||
* @param kinematics The kinematics for the robot drivetrain.
|
||||
* @param wheelSpeeds A function that supplies the speeds of the left
|
||||
* and right sides of the robot drive.
|
||||
* @param leftController The PIDController for the left side of the robot
|
||||
* drive.
|
||||
* @param rightController The PIDController for the right side of the robot
|
||||
* drive.
|
||||
* @param output A function that consumes the computed left and right
|
||||
* outputs (in volts) for the robot drive.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
RamseteCommand(frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::RamseteController controller,
|
||||
frc::SimpleMotorFeedforward<units::meters> feedforward,
|
||||
frc::DifferentialDriveKinematics kinematics,
|
||||
std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
|
||||
frc::PIDController leftController,
|
||||
frc::PIDController rightController,
|
||||
std::function<void(units::volt_t, units::volt_t)> output,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a new RamseteCommand that, when executed, will follow the
|
||||
@@ -140,31 +103,7 @@ class RamseteCommand : public CommandHelper<Command, RamseteCommand> {
|
||||
std::function<void(units::meters_per_second_t,
|
||||
units::meters_per_second_t)>
|
||||
output,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Constructs a new RamseteCommand that, when executed, will follow the
|
||||
* provided trajectory. Performs no PID control and calculates no
|
||||
* feedforwards; outputs are the raw wheel speeds from the RAMSETE controller,
|
||||
* and will need to be converted into a usable form by the user.
|
||||
*
|
||||
* @param trajectory The trajectory to follow.
|
||||
* @param pose A function that supplies the robot pose - use one of
|
||||
* the odometry classes to provide this.
|
||||
* @param controller The RAMSETE controller used to follow the
|
||||
* trajectory.
|
||||
* @param kinematics The kinematics for the robot drivetrain.
|
||||
* @param output A function that consumes the computed left and right
|
||||
* wheel speeds.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
RamseteCommand(frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::RamseteController controller,
|
||||
frc::DifferentialDriveKinematics kinematics,
|
||||
std::function<void(units::meters_per_second_t,
|
||||
units::meters_per_second_t)>
|
||||
output,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
void Initialize() override;
|
||||
|
||||
|
||||
@@ -0,0 +1,46 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <initializer_list>
|
||||
#include <span>
|
||||
#include <vector>
|
||||
|
||||
#include "frc2/command/Subsystem.h"
|
||||
|
||||
namespace frc2 {
|
||||
|
||||
/**
|
||||
* Represents requirements for a command, which is a set of (pointers to)
|
||||
* subsystems. This class is implicitly convertible from std::initializer_list
|
||||
* and std::span.
|
||||
*/
|
||||
class Requirements {
|
||||
public:
|
||||
// NOLINTNEXTLINE
|
||||
/*implicit*/ Requirements(std::initializer_list<Subsystem*> requirements)
|
||||
: m_subsystems{requirements.begin(), requirements.end()} {}
|
||||
|
||||
// NOLINTNEXTLINE
|
||||
/*implicit*/ Requirements(std::span<Subsystem* const> requirements)
|
||||
: m_subsystems{requirements.begin(), requirements.end()} {}
|
||||
|
||||
Requirements() = default;
|
||||
|
||||
Requirements(const Requirements&) = default;
|
||||
|
||||
std::vector<Subsystem*>::const_iterator begin() const {
|
||||
return m_subsystems.begin();
|
||||
}
|
||||
|
||||
std::vector<Subsystem*>::const_iterator end() const {
|
||||
return m_subsystems.end();
|
||||
}
|
||||
|
||||
private:
|
||||
std::vector<Subsystem*> m_subsystems;
|
||||
};
|
||||
|
||||
} // namespace frc2
|
||||
@@ -22,16 +22,6 @@ namespace frc2 {
|
||||
*/
|
||||
class RunCommand : public CommandHelper<FunctionalCommand, RunCommand> {
|
||||
public:
|
||||
/**
|
||||
* Creates a new RunCommand. The Runnable will be run continuously until the
|
||||
* command ends. Does not run when disabled.
|
||||
*
|
||||
* @param toRun the Runnable to run
|
||||
* @param requirements the subsystems to require
|
||||
*/
|
||||
RunCommand(std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Creates a new RunCommand. The Runnable will be run continuously until the
|
||||
* command ends. Does not run when disabled.
|
||||
@@ -40,7 +30,7 @@ class RunCommand : public CommandHelper<FunctionalCommand, RunCommand> {
|
||||
* @param requirements the subsystems to require
|
||||
*/
|
||||
explicit RunCommand(std::function<void()> toRun,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
RunCommand(RunCommand&& other) = default;
|
||||
|
||||
|
||||
@@ -33,18 +33,7 @@ class StartEndCommand
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
StartEndCommand(std::function<void()> onInit, std::function<void()> onEnd,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
|
||||
/**
|
||||
* Creates a new StartEndCommand. Will run the given runnables when the
|
||||
* command starts and when it ends.
|
||||
*
|
||||
* @param onInit the Runnable to run on command init
|
||||
* @param onEnd the Runnable to run on command end
|
||||
* @param requirements the subsystems required by this command
|
||||
*/
|
||||
StartEndCommand(std::function<void()> onInit, std::function<void()> onEnd,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
StartEndCommand(StartEndCommand&& other) = default;
|
||||
|
||||
|
||||
@@ -94,7 +94,7 @@ class SwerveControllerCommand
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
|
||||
output,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a new SwerveControllerCommand that when executed will follow the
|
||||
@@ -132,82 +132,7 @@ class SwerveControllerCommand
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
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. This command will not return output voltages but
|
||||
* rather raw module states from the position controllers which need to be put
|
||||
* into a velocity PID.
|
||||
*
|
||||
* <p>Note: The controllers will *not* set the outputVolts to zero upon
|
||||
* completion of the path- this is left to the user, since it is not
|
||||
* appropriate for paths with nonstationary endstates.
|
||||
*
|
||||
*
|
||||
* @param trajectory The trajectory to follow.
|
||||
* @param pose A function that supplies the robot pose,
|
||||
* provided by the odometry class.
|
||||
* @param kinematics The kinematics for the robot drivetrain.
|
||||
* @param xController The Trajectory Tracker PID controller
|
||||
* for the robot's x position.
|
||||
* @param yController The Trajectory Tracker PID controller
|
||||
* for the robot's y position.
|
||||
* @param thetaController The Trajectory Tracker PID controller
|
||||
* for angle for the robot.
|
||||
* @param desiredRotation The angle that the drivetrain should be
|
||||
* facing. This is sampled at each time step.
|
||||
* @param output The raw output module states from the
|
||||
* position controllers.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
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,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a new SwerveControllerCommand that when executed will follow the
|
||||
* provided trajectory. This command will not return output voltages but
|
||||
* rather raw module states from the position controllers which need to be put
|
||||
* into a velocity PID.
|
||||
*
|
||||
* <p>Note: The controllers will *not* set the outputVolts to zero upon
|
||||
* completion of the path- this is left to the user, since it is not
|
||||
* appropriate for paths with nonstationary endstates.
|
||||
*
|
||||
* <p>Note 2: The final rotation of the robot will be set to the rotation of
|
||||
* the final pose in the trajectory. The robot will not follow the rotations
|
||||
* from the poses at each timestep. If alternate rotation behavior is desired,
|
||||
* the other constructor with a supplier for rotation should be used.
|
||||
*
|
||||
* @param trajectory The trajectory to follow.
|
||||
* @param pose A function that supplies the robot pose,
|
||||
* provided by the odometry class.
|
||||
* @param kinematics The kinematics for the robot drivetrain.
|
||||
* @param xController The Trajectory Tracker PID controller
|
||||
* for the robot's x position.
|
||||
* @param yController The Trajectory Tracker PID controller
|
||||
* for the robot's y position.
|
||||
* @param thetaController The Trajectory Tracker PID controller
|
||||
* for angle for the robot.
|
||||
* @param output The raw output module states from the
|
||||
* position controllers.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
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<void(std::array<frc::SwerveModuleState, NumModules>)>
|
||||
output,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a new SwerveControllerCommand that when executed will follow the
|
||||
@@ -237,7 +162,7 @@ class SwerveControllerCommand
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
|
||||
output,
|
||||
std::initializer_list<Subsystem*> requirements);
|
||||
Requirements requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a new SwerveControllerCommand that when executed will follow the
|
||||
@@ -269,70 +194,7 @@ class SwerveControllerCommand
|
||||
frc::HolonomicDriveController controller,
|
||||
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. This command will not return output voltages but
|
||||
* rather raw module states from the position controllers which need to be put
|
||||
* into a velocity PID.
|
||||
*
|
||||
* <p>Note: The controllers will *not* set the outputVolts to zero upon
|
||||
* completion of the path- this is left to the user, since it is not
|
||||
* appropriate for paths with nonstationary endstates.
|
||||
*
|
||||
*
|
||||
* @param trajectory The trajectory to follow.
|
||||
* @param pose A function that supplies the robot pose,
|
||||
* provided by the odometry class.
|
||||
* @param kinematics The kinematics for the robot drivetrain.
|
||||
* @param controller The HolonomicDriveController for the robot.
|
||||
* @param desiredRotation The angle that the drivetrain should be
|
||||
* facing. This is sampled at each time step.
|
||||
* @param output The raw output module states from the
|
||||
* position controllers.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc::HolonomicDriveController controller,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
|
||||
output,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
|
||||
/**
|
||||
* Constructs a new SwerveControllerCommand that when executed will follow the
|
||||
* provided trajectory. This command will not return output voltages but
|
||||
* rather raw module states from the position controllers which need to be put
|
||||
* into a velocity PID.
|
||||
*
|
||||
* <p>Note: The controllers will *not* set the outputVolts to zero upon
|
||||
* completion of the path- this is left to the user, since it is not
|
||||
* appropriate for paths with nonstationary endstates.
|
||||
*
|
||||
* <p>Note 2: The final rotation of the robot will be set to the rotation of
|
||||
* the final pose in the trajectory. The robot will not follow the rotations
|
||||
* from the poses at each timestep. If alternate rotation behavior is desired,
|
||||
* the other constructor with a supplier for rotation should be used.
|
||||
*
|
||||
* @param trajectory The trajectory to follow.
|
||||
* @param pose A function that supplies the robot pose,
|
||||
* provided by the odometry class.
|
||||
* @param kinematics The kinematics for the robot drivetrain.
|
||||
* @param controller The HolonomicDriveController for the drivetrain.
|
||||
* @param output The raw output module states from the
|
||||
* position controllers.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc::HolonomicDriveController controller,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
|
||||
output,
|
||||
std::span<Subsystem* const> requirements = {});
|
||||
Requirements requirements = {});
|
||||
|
||||
void Initialize() override;
|
||||
|
||||
|
||||
@@ -20,7 +20,7 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
Requirements requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
@@ -37,41 +37,7 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
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)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(xController, yController, thetaController),
|
||||
m_outputStates(output) {
|
||||
this->AddRequirements(requirements);
|
||||
}
|
||||
|
||||
template <size_t NumModules>
|
||||
SwerveControllerCommand<NumModules>::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,
|
||||
std::span<Subsystem* const> requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(xController, yController, thetaController),
|
||||
m_desiredRotation(std::move(desiredRotation)),
|
||||
m_outputStates(output) {
|
||||
this->AddRequirements(requirements);
|
||||
}
|
||||
|
||||
template <size_t NumModules>
|
||||
SwerveControllerCommand<NumModules>::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<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
std::span<Subsystem* const> requirements)
|
||||
Requirements requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
@@ -87,7 +53,7 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::HolonomicDriveController controller,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
Requirements requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
@@ -103,39 +69,7 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc::HolonomicDriveController controller,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(std::move(controller)),
|
||||
m_outputStates(output) {
|
||||
this->AddRequirements(requirements);
|
||||
}
|
||||
|
||||
template <size_t NumModules>
|
||||
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc::HolonomicDriveController controller,
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
std::span<Subsystem* const> requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(std::move(controller)),
|
||||
m_desiredRotation(std::move(desiredRotation)),
|
||||
m_outputStates(output) {
|
||||
this->AddRequirements(requirements);
|
||||
}
|
||||
|
||||
template <size_t NumModules>
|
||||
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
|
||||
frc::SwerveDriveKinematics<NumModules> kinematics,
|
||||
frc::HolonomicDriveController controller,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
std::span<Subsystem* const> requirements)
|
||||
Requirements requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
|
||||
@@ -47,30 +47,7 @@ class TrapezoidProfileCommand
|
||||
std::function<void(State)> output,
|
||||
std::function<State()> goal,
|
||||
std::function<State()> currentState,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_profile(profile),
|
||||
m_output(output),
|
||||
m_goal(goal),
|
||||
m_currentState(currentState) {
|
||||
this->AddRequirements(requirements);
|
||||
m_newAPI = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a new TrapezoidProfileCommand that will execute the given
|
||||
* TrapezoidalProfile. Output will be piped to the provided consumer function.
|
||||
*
|
||||
* @param profile The motion profile to execute.
|
||||
* @param output The consumer for the profile output.
|
||||
* @param goal The supplier for the desired state
|
||||
* @param currentState The current state
|
||||
* @param requirements The list of requirements.
|
||||
*/
|
||||
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
|
||||
std::function<void(State)> output,
|
||||
std::function<State()> goal,
|
||||
std::function<State()> currentState,
|
||||
std::span<Subsystem* const> requirements = {})
|
||||
Requirements requirements = {})
|
||||
: m_profile(profile),
|
||||
m_output(output),
|
||||
m_goal(goal),
|
||||
@@ -94,28 +71,7 @@ class TrapezoidProfileCommand
|
||||
"current state. This allows you to change goals at runtime.")
|
||||
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
|
||||
std::function<void(State)> output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_profile(profile), m_output(output) {
|
||||
this->AddRequirements(requirements);
|
||||
m_newAPI = false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a new TrapezoidProfileCommand that will execute the given
|
||||
* TrapezoidalProfile. Output will be piped to the provided consumer function.
|
||||
*
|
||||
* @param profile The motion profile to execute.
|
||||
* @param output The consumer for the profile output.
|
||||
* @param requirements The list of requirements.
|
||||
* @deprecated The new constructor allows you to pass in a supplier for
|
||||
* desired and current state. This allows you to change goals at runtime.
|
||||
*/
|
||||
WPI_DEPRECATED(
|
||||
"The new constructor allows you to pass in a supplier for desired and "
|
||||
"current state. This allows you to change goals at runtime.")
|
||||
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
|
||||
std::function<void(State)> output,
|
||||
std::span<Subsystem* const> requirements = {})
|
||||
Requirements requirements = {})
|
||||
: m_profile(profile), m_output(output) {
|
||||
this->AddRequirements(requirements);
|
||||
m_newAPI = false;
|
||||
|
||||
Reference in New Issue
Block a user