Add ArrayRef overloads to new command classes (#2216)

Also default requirements to {} in all cases for consistency.
This commit is contained in:
Peter Johnson
2020-01-01 20:09:17 -08:00
committed by GitHub
parent 6190fcb237
commit 32c62449be
30 changed files with 773 additions and 49 deletions

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -51,6 +51,13 @@ ParallelRaceGroup Command::WithInterrupt(std::function<bool()> condition) && {
SequentialCommandGroup Command::BeforeStarting(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements) && {
return std::move(*this).BeforeStarting(
std::move(toRun),
wpi::makeArrayRef(requirements.begin(), requirements.end()));
}
SequentialCommandGroup Command::BeforeStarting(
std::function<void()> toRun, wpi::ArrayRef<Subsystem*> requirements) && {
std::vector<std::unique_ptr<Command>> temp;
temp.emplace_back(
std::make_unique<InstantCommand>(std::move(toRun), requirements));
@@ -61,6 +68,13 @@ SequentialCommandGroup Command::BeforeStarting(
SequentialCommandGroup Command::AndThen(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements) && {
return std::move(*this).AndThen(
std::move(toRun),
wpi::makeArrayRef(requirements.begin(), requirements.end()));
}
SequentialCommandGroup Command::AndThen(
std::function<void()> toRun, wpi::ArrayRef<Subsystem*> requirements) && {
std::vector<std::unique_ptr<Command>> temp;
temp.emplace_back(std::move(*this).TransferOwnership());
temp.emplace_back(

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -21,6 +21,10 @@ void CommandBase::AddRequirements(
m_requirements.insert(requirements.begin(), requirements.end());
}
void CommandBase::AddRequirements(wpi::ArrayRef<Subsystem*> requirements) {
m_requirements.insert(requirements.begin(), requirements.end());
}
void CommandBase::AddRequirements(wpi::SmallSet<Subsystem*, 4> requirements) {
m_requirements.insert(requirements.begin(), requirements.end());
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -248,6 +248,12 @@ void CommandScheduler::RegisterSubsystem(
}
}
void CommandScheduler::RegisterSubsystem(wpi::ArrayRef<Subsystem*> subsystems) {
for (auto* subsystem : subsystems) {
RegisterSubsystem(subsystem);
}
}
void CommandScheduler::UnregisterSubsystem(
std::initializer_list<Subsystem*> subsystems) {
for (auto* subsystem : subsystems) {
@@ -255,6 +261,13 @@ void CommandScheduler::UnregisterSubsystem(
}
}
void CommandScheduler::UnregisterSubsystem(
wpi::ArrayRef<Subsystem*> subsystems) {
for (auto* subsystem : subsystems) {
UnregisterSubsystem(subsystem);
}
}
Command* CommandScheduler::GetDefaultCommand(const Subsystem* subsystem) const {
auto&& find = m_impl->subsystems.find(subsystem);
if (find != m_impl->subsystems.end()) {

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -20,6 +20,18 @@ FunctionalCommand::FunctionalCommand(
AddRequirements(requirements);
}
FunctionalCommand::FunctionalCommand(std::function<void()> onInit,
std::function<void()> onExecute,
std::function<void(bool)> onEnd,
std::function<bool()> isFinished,
wpi::ArrayRef<Subsystem*> requirements)
: m_onInit{std::move(onInit)},
m_onExecute{std::move(onExecute)},
m_onEnd{std::move(onEnd)},
m_isFinished{std::move(isFinished)} {
AddRequirements(requirements);
}
void FunctionalCommand::Initialize() { m_onInit(); }
void FunctionalCommand::Execute() { m_onExecute(); }

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -15,6 +15,12 @@ InstantCommand::InstantCommand(std::function<void()> toRun,
AddRequirements(requirements);
}
InstantCommand::InstantCommand(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements)
: m_toRun{std::move(toRun)} {
AddRequirements(requirements);
}
InstantCommand::InstantCommand() : m_toRun{[] {}} {}
void InstantCommand::Initialize() { m_toRun(); }

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -50,6 +50,46 @@ MecanumControllerCommand::MecanumControllerCommand(
AddRequirements(requirements);
}
MecanumControllerCommand::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,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
m_feedforward(feedforward),
m_kinematics(kinematics),
m_xController(std::make_unique<frc2::PIDController>(xController)),
m_yController(std::make_unique<frc2::PIDController>(yController)),
m_thetaController(
std::make_unique<frc::ProfiledPIDController<units::radians>>(
thetaController)),
m_maxWheelVelocity(maxWheelVelocity),
m_frontLeftController(
std::make_unique<frc2::PIDController>(frontLeftController)),
m_rearLeftController(
std::make_unique<frc2::PIDController>(rearLeftController)),
m_frontRightController(
std::make_unique<frc2::PIDController>(frontRightController)),
m_rearRightController(
std::make_unique<frc2::PIDController>(rearRightController)),
m_currentWheelSpeeds(currentWheelSpeeds),
m_outputVolts(output),
m_usePID(true) {
AddRequirements(requirements);
}
MecanumControllerCommand::MecanumControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
@@ -74,6 +114,30 @@ MecanumControllerCommand::MecanumControllerCommand(
AddRequirements(requirements);
}
MecanumControllerCommand::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,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
m_kinematics(kinematics),
m_xController(std::make_unique<frc2::PIDController>(xController)),
m_yController(std::make_unique<frc2::PIDController>(yController)),
m_thetaController(
std::make_unique<frc::ProfiledPIDController<units::radians>>(
thetaController)),
m_maxWheelVelocity(maxWheelVelocity),
m_outputVel(output),
m_usePID(false) {
AddRequirements(requirements);
}
void MecanumControllerCommand::Initialize() {
m_prevTime = 0_s;
auto initialState = m_trajectory.Sample(0_s);

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -16,6 +16,13 @@ NotifierCommand::NotifierCommand(std::function<void()> toRun,
AddRequirements(requirements);
}
NotifierCommand::NotifierCommand(std::function<void()> toRun,
units::second_t period,
wpi::ArrayRef<Subsystem*> requirements)
: m_toRun(toRun), m_notifier{std::move(toRun)}, m_period{period} {
AddRequirements(requirements);
}
NotifierCommand::NotifierCommand(NotifierCommand&& other)
: CommandHelper(std::move(other)),
m_toRun(other.m_toRun),

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -21,6 +21,18 @@ PIDCommand::PIDCommand(PIDController controller,
AddRequirements(requirements);
}
PIDCommand::PIDCommand(PIDController controller,
std::function<double()> measurementSource,
std::function<double()> setpointSource,
std::function<void(double)> useOutput,
wpi::ArrayRef<Subsystem*> requirements)
: m_controller{controller},
m_measurement{std::move(measurementSource)},
m_setpoint{std::move(setpointSource)},
m_useOutput{std::move(useOutput)} {
AddRequirements(requirements);
}
PIDCommand::PIDCommand(PIDController controller,
std::function<double()> measurementSource,
double setpoint, std::function<void(double)> useOutput,
@@ -28,6 +40,13 @@ PIDCommand::PIDCommand(PIDController controller,
: PIDCommand(controller, measurementSource, [setpoint] { return setpoint; },
useOutput, requirements) {}
PIDCommand::PIDCommand(PIDController controller,
std::function<double()> measurementSource,
double setpoint, std::function<void(double)> useOutput,
wpi::ArrayRef<Subsystem*> requirements)
: PIDCommand(controller, measurementSource, [setpoint] { return setpoint; },
useOutput, requirements) {}
void PIDCommand::Initialize() { m_controller.Reset(); }
void PIDCommand::Execute() {

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -32,6 +32,28 @@ RamseteCommand::RamseteCommand(
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,
frc2::PIDController leftController, frc2::PIDController rightController,
std::function<void(volt_t, volt_t)> output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
m_controller(controller),
m_feedforward(feedforward),
m_kinematics(kinematics),
m_speeds(wheelSpeeds),
m_leftController(std::make_unique<frc2::PIDController>(leftController)),
m_rightController(std::make_unique<frc2::PIDController>(rightController)),
m_outputVolts(output),
m_usePID(true) {
AddRequirements(requirements);
}
RamseteCommand::RamseteCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::RamseteController controller,
@@ -48,6 +70,22 @@ RamseteCommand::RamseteCommand(
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,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
m_controller(controller),
m_kinematics(kinematics),
m_outputVel(output),
m_usePID(false) {
AddRequirements(requirements);
}
void RamseteCommand::Initialize() {
m_prevTime = 0_s;
auto initialState = m_trajectory.Sample(0_s);

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -15,4 +15,10 @@ RunCommand::RunCommand(std::function<void()> toRun,
AddRequirements(requirements);
}
RunCommand::RunCommand(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements)
: m_toRun{std::move(toRun)} {
AddRequirements(requirements);
}
void RunCommand::Execute() { m_toRun(); }

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -16,6 +16,13 @@ StartEndCommand::StartEndCommand(std::function<void()> onInit,
AddRequirements(requirements);
}
StartEndCommand::StartEndCommand(std::function<void()> onInit,
std::function<void()> onEnd,
wpi::ArrayRef<Subsystem*> requirements)
: m_onInit{std::move(onInit)}, m_onEnd{std::move(onEnd)} {
AddRequirements(requirements);
}
StartEndCommand::StartEndCommand(const StartEndCommand& other)
: CommandHelper(other) {
m_onInit = other.m_onInit;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -22,6 +22,12 @@ Button Button::WhenPressed(std::function<void()> toRun,
return *this;
}
Button Button::WhenPressed(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
WhenActive(std::move(toRun), requirements);
return *this;
}
Button Button::WhileHeld(Command* command, bool interruptible) {
WhileActiveContinous(command, interruptible);
return *this;
@@ -33,6 +39,12 @@ Button Button::WhileHeld(std::function<void()> toRun,
return *this;
}
Button Button::WhileHeld(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
WhileActiveContinous(std::move(toRun), requirements);
return *this;
}
Button Button::WhenHeld(Command* command, bool interruptible) {
WhileActiveOnce(command, interruptible);
return *this;
@@ -49,6 +61,12 @@ Button Button::WhenReleased(std::function<void()> toRun,
return *this;
}
Button Button::WhenReleased(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
WhenInactive(std::move(toRun), requirements);
return *this;
}
Button Button::ToggleWhenPressed(Command* command, bool interruptible) {
ToggleWhenActive(command, interruptible);
return *this;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -30,6 +30,12 @@ Trigger Trigger::WhenActive(Command* command, bool interruptible) {
Trigger Trigger::WhenActive(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements) {
return WhenActive(std::move(toRun), wpi::makeArrayRef(requirements.begin(),
requirements.end()));
}
Trigger Trigger::WhenActive(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
return WhenActive(InstantCommand(std::move(toRun), requirements));
}
@@ -52,6 +58,13 @@ Trigger Trigger::WhileActiveContinous(Command* command, bool interruptible) {
Trigger Trigger::WhileActiveContinous(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements) {
return WhileActiveContinous(
std::move(toRun),
wpi::makeArrayRef(requirements.begin(), requirements.end()));
}
Trigger Trigger::WhileActiveContinous(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
return WhileActiveContinous(InstantCommand(std::move(toRun), requirements));
}
@@ -87,6 +100,12 @@ Trigger Trigger::WhenInactive(Command* command, bool interruptible) {
Trigger Trigger::WhenInactive(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements) {
return WhenInactive(std::move(toRun), wpi::makeArrayRef(requirements.begin(),
requirements.end()));
}
Trigger Trigger::WhenInactive(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
return WhenInactive(InstantCommand(std::move(toRun), requirements));
}