mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[commands] Add C++ Requirements struct (#5504)
This commit is contained in:
@@ -43,11 +43,7 @@ wpi::SmallSet<Subsystem*, 4> Command::GetRequirements() const {
|
||||
return m_requirements;
|
||||
}
|
||||
|
||||
void Command::AddRequirements(std::initializer_list<Subsystem*> requirements) {
|
||||
m_requirements.insert(requirements.begin(), requirements.end());
|
||||
}
|
||||
|
||||
void Command::AddRequirements(std::span<Subsystem* const> requirements) {
|
||||
void Command::AddRequirements(Requirements requirements) {
|
||||
m_requirements.insert(requirements.begin(), requirements.end());
|
||||
}
|
||||
|
||||
@@ -96,27 +92,14 @@ CommandPtr Command::WithInterruptBehavior(
|
||||
return std::move(*this).ToPtr().WithInterruptBehavior(interruptBehavior);
|
||||
}
|
||||
|
||||
CommandPtr Command::BeforeStarting(
|
||||
std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements) && {
|
||||
return std::move(*this).BeforeStarting(
|
||||
std::move(toRun), {requirements.begin(), requirements.end()});
|
||||
}
|
||||
|
||||
CommandPtr Command::BeforeStarting(
|
||||
std::function<void()> toRun, std::span<Subsystem* const> requirements) && {
|
||||
CommandPtr Command::BeforeStarting(std::function<void()> toRun,
|
||||
Requirements requirements) && {
|
||||
return std::move(*this).ToPtr().BeforeStarting(std::move(toRun),
|
||||
requirements);
|
||||
}
|
||||
|
||||
CommandPtr Command::AndThen(std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements) && {
|
||||
return std::move(*this).AndThen(std::move(toRun),
|
||||
{requirements.begin(), requirements.end()});
|
||||
}
|
||||
|
||||
CommandPtr Command::AndThen(std::function<void()> toRun,
|
||||
std::span<Subsystem* const> requirements) && {
|
||||
Requirements requirements) && {
|
||||
return std::move(*this).ToPtr().AndThen(std::move(toRun), requirements);
|
||||
}
|
||||
|
||||
|
||||
@@ -86,15 +86,7 @@ CommandPtr CommandPtr::WithInterruptBehavior(
|
||||
}
|
||||
|
||||
CommandPtr CommandPtr::AndThen(std::function<void()> toRun,
|
||||
std::span<Subsystem* const> requirements) && {
|
||||
AssertValid();
|
||||
return std::move(*this).AndThen(CommandPtr(
|
||||
std::make_unique<InstantCommand>(std::move(toRun), requirements)));
|
||||
}
|
||||
|
||||
CommandPtr CommandPtr::AndThen(
|
||||
std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements) && {
|
||||
Requirements requirements) && {
|
||||
AssertValid();
|
||||
return std::move(*this).AndThen(CommandPtr(
|
||||
std::make_unique<InstantCommand>(std::move(toRun), requirements)));
|
||||
@@ -109,16 +101,8 @@ CommandPtr CommandPtr::AndThen(CommandPtr&& next) && {
|
||||
return std::move(*this);
|
||||
}
|
||||
|
||||
CommandPtr CommandPtr::BeforeStarting(
|
||||
std::function<void()> toRun, std::span<Subsystem* const> requirements) && {
|
||||
AssertValid();
|
||||
return std::move(*this).BeforeStarting(CommandPtr(
|
||||
std::make_unique<InstantCommand>(std::move(toRun), requirements)));
|
||||
}
|
||||
|
||||
CommandPtr CommandPtr::BeforeStarting(
|
||||
std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements) && {
|
||||
CommandPtr CommandPtr::BeforeStarting(std::function<void()> toRun,
|
||||
Requirements requirements) && {
|
||||
AssertValid();
|
||||
return std::move(*this).BeforeStarting(CommandPtr(
|
||||
std::make_unique<InstantCommand>(std::move(toRun), requirements)));
|
||||
|
||||
@@ -29,36 +29,16 @@ CommandPtr cmd::Idle() {
|
||||
}
|
||||
|
||||
CommandPtr cmd::RunOnce(std::function<void()> action,
|
||||
std::initializer_list<Subsystem*> requirements) {
|
||||
Requirements requirements) {
|
||||
return InstantCommand(std::move(action), requirements).ToPtr();
|
||||
}
|
||||
|
||||
CommandPtr cmd::RunOnce(std::function<void()> action,
|
||||
std::span<Subsystem* const> requirements) {
|
||||
return InstantCommand(std::move(action), requirements).ToPtr();
|
||||
}
|
||||
|
||||
CommandPtr cmd::Run(std::function<void()> action,
|
||||
std::initializer_list<Subsystem*> requirements) {
|
||||
return RunCommand(std::move(action), requirements).ToPtr();
|
||||
}
|
||||
|
||||
CommandPtr cmd::Run(std::function<void()> action,
|
||||
std::span<Subsystem* const> requirements) {
|
||||
CommandPtr cmd::Run(std::function<void()> action, Requirements requirements) {
|
||||
return RunCommand(std::move(action), requirements).ToPtr();
|
||||
}
|
||||
|
||||
CommandPtr cmd::StartEnd(std::function<void()> start, std::function<void()> end,
|
||||
std::initializer_list<Subsystem*> requirements) {
|
||||
return FunctionalCommand(
|
||||
std::move(start), [] {},
|
||||
[end = std::move(end)](bool interrupted) { end(); },
|
||||
[] { return false; }, requirements)
|
||||
.ToPtr();
|
||||
}
|
||||
|
||||
CommandPtr cmd::StartEnd(std::function<void()> start, std::function<void()> end,
|
||||
std::span<Subsystem* const> requirements) {
|
||||
Requirements requirements) {
|
||||
return FunctionalCommand(
|
||||
std::move(start), [] {},
|
||||
[end = std::move(end)](bool interrupted) { end(); },
|
||||
@@ -67,15 +47,7 @@ CommandPtr cmd::StartEnd(std::function<void()> start, std::function<void()> end,
|
||||
}
|
||||
|
||||
CommandPtr cmd::RunEnd(std::function<void()> run, std::function<void()> end,
|
||||
std::initializer_list<Subsystem*> requirements) {
|
||||
return FunctionalCommand([] {}, std::move(run),
|
||||
[end = std::move(end)](bool interrupted) { end(); },
|
||||
[] { return false; }, requirements)
|
||||
.ToPtr();
|
||||
}
|
||||
|
||||
CommandPtr cmd::RunEnd(std::function<void()> run, std::function<void()> end,
|
||||
std::span<Subsystem* const> requirements) {
|
||||
Requirements requirements) {
|
||||
return FunctionalCommand([] {}, std::move(run),
|
||||
[end = std::move(end)](bool interrupted) { end(); },
|
||||
[] { return false; }, requirements)
|
||||
|
||||
@@ -6,22 +6,11 @@
|
||||
|
||||
using namespace frc2;
|
||||
|
||||
FunctionalCommand::FunctionalCommand(
|
||||
std::function<void()> onInit, std::function<void()> onExecute,
|
||||
std::function<void(bool)> onEnd, std::function<bool()> isFinished,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_onInit{std::move(onInit)},
|
||||
m_onExecute{std::move(onExecute)},
|
||||
m_onEnd{std::move(onEnd)},
|
||||
m_isFinished{std::move(isFinished)} {
|
||||
AddRequirements(requirements);
|
||||
}
|
||||
|
||||
FunctionalCommand::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)
|
||||
: m_onInit{std::move(onInit)},
|
||||
m_onExecute{std::move(onExecute)},
|
||||
m_onEnd{std::move(onEnd)},
|
||||
|
||||
@@ -7,13 +7,7 @@
|
||||
using namespace frc2;
|
||||
|
||||
InstantCommand::InstantCommand(std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: CommandHelper(
|
||||
std::move(toRun), [] {}, [](bool interrupted) {}, [] { return true; },
|
||||
requirements) {}
|
||||
|
||||
InstantCommand::InstantCommand(std::function<void()> toRun,
|
||||
std::span<Subsystem* const> requirements)
|
||||
Requirements requirements)
|
||||
: CommandHelper(
|
||||
std::move(toRun), [] {}, [](bool interrupted) {}, [] { return true; },
|
||||
requirements) {}
|
||||
|
||||
@@ -24,7 +24,7 @@ MecanumControllerCommand::MecanumControllerCommand(
|
||||
std::function<void(units::volt_t, units::volt_t, units::volt_t,
|
||||
units::volt_t)>
|
||||
output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
Requirements requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_feedforward(feedforward),
|
||||
@@ -61,81 +61,7 @@ MecanumControllerCommand::MecanumControllerCommand(
|
||||
std::function<void(units::volt_t, units::volt_t, units::volt_t,
|
||||
units::volt_t)>
|
||||
output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_feedforward(feedforward),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(xController, yController, thetaController),
|
||||
m_maxWheelVelocity(maxWheelVelocity),
|
||||
m_frontLeftController(
|
||||
std::make_unique<frc::PIDController>(frontLeftController)),
|
||||
m_rearLeftController(
|
||||
std::make_unique<frc::PIDController>(rearLeftController)),
|
||||
m_frontRightController(
|
||||
std::make_unique<frc::PIDController>(frontRightController)),
|
||||
m_rearRightController(
|
||||
std::make_unique<frc::PIDController>(rearRightController)),
|
||||
m_currentWheelSpeeds(std::move(currentWheelSpeeds)),
|
||||
m_outputVolts(std::move(output)),
|
||||
m_usePID(true) {
|
||||
AddRequirements(requirements);
|
||||
}
|
||||
|
||||
MecanumControllerCommand::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)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_feedforward(feedforward),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(xController, yController, thetaController),
|
||||
m_desiredRotation(std::move(desiredRotation)),
|
||||
m_maxWheelVelocity(maxWheelVelocity),
|
||||
m_frontLeftController(
|
||||
std::make_unique<frc::PIDController>(frontLeftController)),
|
||||
m_rearLeftController(
|
||||
std::make_unique<frc::PIDController>(rearLeftController)),
|
||||
m_frontRightController(
|
||||
std::make_unique<frc::PIDController>(frontRightController)),
|
||||
m_rearRightController(
|
||||
std::make_unique<frc::PIDController>(rearRightController)),
|
||||
m_currentWheelSpeeds(std::move(currentWheelSpeeds)),
|
||||
m_outputVolts(std::move(output)),
|
||||
m_usePID(true) {
|
||||
AddRequirements(requirements);
|
||||
}
|
||||
|
||||
MecanumControllerCommand::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)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_feedforward(feedforward),
|
||||
@@ -166,7 +92,7 @@ MecanumControllerCommand::MecanumControllerCommand(
|
||||
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)
|
||||
Requirements requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
@@ -187,49 +113,7 @@ MecanumControllerCommand::MecanumControllerCommand(
|
||||
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)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(xController, yController, thetaController),
|
||||
m_maxWheelVelocity(maxWheelVelocity),
|
||||
m_outputVel(std::move(output)),
|
||||
m_usePID(false) {
|
||||
AddRequirements(requirements);
|
||||
}
|
||||
|
||||
MecanumControllerCommand::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)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(xController, yController, thetaController),
|
||||
m_desiredRotation(std::move(desiredRotation)),
|
||||
m_maxWheelVelocity(maxWheelVelocity),
|
||||
m_outputVel(std::move(output)),
|
||||
m_usePID(false) {
|
||||
AddRequirements(requirements);
|
||||
}
|
||||
|
||||
MecanumControllerCommand::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)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
|
||||
@@ -8,14 +8,7 @@ using namespace frc2;
|
||||
|
||||
NotifierCommand::NotifierCommand(std::function<void()> toRun,
|
||||
units::second_t period,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_toRun(toRun), m_notifier{std::move(toRun)}, m_period{period} {
|
||||
AddRequirements(requirements);
|
||||
}
|
||||
|
||||
NotifierCommand::NotifierCommand(std::function<void()> toRun,
|
||||
units::second_t period,
|
||||
std::span<Subsystem* const> requirements)
|
||||
Requirements requirements)
|
||||
: m_toRun(toRun), m_notifier{std::move(toRun)}, m_period{period} {
|
||||
AddRequirements(requirements);
|
||||
}
|
||||
|
||||
@@ -12,19 +12,7 @@ PIDCommand::PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource,
|
||||
std::function<double()> setpointSource,
|
||||
std::function<void(double)> useOutput,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_controller{std::move(controller)},
|
||||
m_measurement{std::move(measurementSource)},
|
||||
m_setpoint{std::move(setpointSource)},
|
||||
m_useOutput{std::move(useOutput)} {
|
||||
AddRequirements(requirements);
|
||||
}
|
||||
|
||||
PIDCommand::PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource,
|
||||
std::function<double()> setpointSource,
|
||||
std::function<void(double)> useOutput,
|
||||
std::span<Subsystem* const> requirements)
|
||||
Requirements requirements)
|
||||
: m_controller{std::move(controller)},
|
||||
m_measurement{std::move(measurementSource)},
|
||||
m_setpoint{std::move(setpointSource)},
|
||||
@@ -35,15 +23,7 @@ PIDCommand::PIDCommand(frc::PIDController controller,
|
||||
PIDCommand::PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource,
|
||||
double setpoint, std::function<void(double)> useOutput,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: PIDCommand(
|
||||
controller, measurementSource, [setpoint] { return setpoint; },
|
||||
useOutput, requirements) {}
|
||||
|
||||
PIDCommand::PIDCommand(frc::PIDController controller,
|
||||
std::function<double()> measurementSource,
|
||||
double setpoint, std::function<void(double)> useOutput,
|
||||
std::span<Subsystem* const> requirements)
|
||||
Requirements requirements)
|
||||
: PIDCommand(
|
||||
controller, measurementSource, [setpoint] { return setpoint; },
|
||||
useOutput, requirements) {}
|
||||
|
||||
@@ -18,29 +18,7 @@ RamseteCommand::RamseteCommand(
|
||||
std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
|
||||
frc::PIDController leftController, frc::PIDController rightController,
|
||||
std::function<void(units::volt_t, units::volt_t)> output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_controller(controller),
|
||||
m_feedforward(feedforward),
|
||||
m_kinematics(std::move(kinematics)),
|
||||
m_speeds(std::move(wheelSpeeds)),
|
||||
m_leftController(std::make_unique<frc::PIDController>(leftController)),
|
||||
m_rightController(std::make_unique<frc::PIDController>(rightController)),
|
||||
m_outputVolts(std::move(output)),
|
||||
m_usePID(true) {
|
||||
AddRequirements(requirements);
|
||||
}
|
||||
|
||||
RamseteCommand::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)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_controller(controller),
|
||||
@@ -60,23 +38,7 @@ RamseteCommand::RamseteCommand(
|
||||
frc::DifferentialDriveKinematics kinematics,
|
||||
std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
|
||||
output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_controller(controller),
|
||||
m_kinematics(std::move(kinematics)),
|
||||
m_outputVel(std::move(output)),
|
||||
m_usePID(false) {
|
||||
AddRequirements(requirements);
|
||||
}
|
||||
|
||||
RamseteCommand::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)
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_controller(controller),
|
||||
|
||||
@@ -6,12 +6,6 @@
|
||||
|
||||
using namespace frc2;
|
||||
|
||||
RunCommand::RunCommand(std::function<void()> toRun,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: CommandHelper([] {}, std::move(toRun), [](bool interrupted) {},
|
||||
[] { return false; }, requirements) {}
|
||||
|
||||
RunCommand::RunCommand(std::function<void()> toRun,
|
||||
std::span<Subsystem* const> requirements)
|
||||
RunCommand::RunCommand(std::function<void()> toRun, Requirements requirements)
|
||||
: CommandHelper([] {}, std::move(toRun), [](bool interrupted) {},
|
||||
[] { return false; }, requirements) {}
|
||||
|
||||
@@ -8,15 +8,7 @@ using namespace frc2;
|
||||
|
||||
StartEndCommand::StartEndCommand(std::function<void()> onInit,
|
||||
std::function<void()> onEnd,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: CommandHelper(
|
||||
std::move(onInit), [] {},
|
||||
[onEnd = std::move(onEnd)](bool interrupted) { onEnd(); },
|
||||
[] { return false; }, requirements) {}
|
||||
|
||||
StartEndCommand::StartEndCommand(std::function<void()> onInit,
|
||||
std::function<void()> onEnd,
|
||||
std::span<Subsystem* const> requirements)
|
||||
Requirements requirements)
|
||||
: CommandHelper(
|
||||
std::move(onInit), [] {},
|
||||
[onEnd = std::move(onEnd)](bool interrupted) { onEnd(); },
|
||||
|
||||
Reference in New Issue
Block a user