Use wpi::span instead of wpi::ArrayRef across all libraries (#3414)

- Remove ArrayRef.h
- Add SpanExtras.h for a couple of convenience functions
This commit is contained in:
Peter Johnson
2021-06-06 19:51:14 -07:00
committed by GitHub
parent 2abbbd9e70
commit 64f5413253
167 changed files with 974 additions and 1433 deletions

View File

@@ -48,12 +48,11 @@ 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()));
std::move(toRun), {requirements.begin(), requirements.end()});
}
SequentialCommandGroup Command::BeforeStarting(
std::function<void()> toRun, wpi::ArrayRef<Subsystem*> requirements) && {
std::function<void()> toRun, wpi::span<Subsystem* const> requirements) && {
std::vector<std::unique_ptr<Command>> temp;
temp.emplace_back(
std::make_unique<InstantCommand>(std::move(toRun), requirements));
@@ -64,13 +63,12 @@ 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()));
return std::move(*this).AndThen(std::move(toRun),
{requirements.begin(), requirements.end()});
}
SequentialCommandGroup Command::AndThen(
std::function<void()> toRun, wpi::ArrayRef<Subsystem*> requirements) && {
std::function<void()> toRun, wpi::span<Subsystem* const> requirements) && {
std::vector<std::unique_ptr<Command>> temp;
temp.emplace_back(std::move(*this).TransferOwnership());
temp.emplace_back(

View File

@@ -18,7 +18,7 @@ void CommandBase::AddRequirements(
m_requirements.insert(requirements.begin(), requirements.end());
}
void CommandBase::AddRequirements(wpi::ArrayRef<Subsystem*> requirements) {
void CommandBase::AddRequirements(wpi::span<Subsystem* const> requirements) {
m_requirements.insert(requirements.begin(), requirements.end());
}

View File

@@ -6,7 +6,7 @@
using namespace frc2;
bool CommandGroupBase::RequireUngrouped(Command& command) {
bool CommandGroupBase::RequireUngrouped(const Command& command) {
if (command.IsGrouped()) {
throw FRC_MakeError(
frc::err::CommandIllegalUse, "{}",
@@ -15,8 +15,12 @@ bool CommandGroupBase::RequireUngrouped(Command& command) {
return true;
}
bool CommandGroupBase::RequireUngrouped(const Command* command) {
return RequireUngrouped(*command);
}
bool CommandGroupBase::RequireUngrouped(
wpi::ArrayRef<std::unique_ptr<Command>> commands) {
wpi::span<const std::unique_ptr<Command>> commands) {
bool allUngrouped = true;
for (auto&& command : commands) {
allUngrouped &= !command.get()->IsGrouped();
@@ -30,7 +34,7 @@ bool CommandGroupBase::RequireUngrouped(
}
bool CommandGroupBase::RequireUngrouped(
std::initializer_list<Command*> commands) {
std::initializer_list<const Command*> commands) {
bool allUngrouped = true;
for (auto&& command : commands) {
allUngrouped &= !command->IsGrouped();

View File

@@ -161,7 +161,7 @@ void CommandScheduler::Schedule(Command* command) {
}
void CommandScheduler::Schedule(bool interruptible,
wpi::ArrayRef<Command*> commands) {
wpi::span<Command* const> commands) {
for (auto command : commands) {
Schedule(interruptible, command);
}
@@ -174,7 +174,7 @@ void CommandScheduler::Schedule(bool interruptible,
}
}
void CommandScheduler::Schedule(wpi::ArrayRef<Command*> commands) {
void CommandScheduler::Schedule(wpi::span<Command* const> commands) {
for (auto command : commands) {
Schedule(true, command);
}
@@ -284,7 +284,8 @@ void CommandScheduler::RegisterSubsystem(
}
}
void CommandScheduler::RegisterSubsystem(wpi::ArrayRef<Subsystem*> subsystems) {
void CommandScheduler::RegisterSubsystem(
wpi::span<Subsystem* const> subsystems) {
for (auto* subsystem : subsystems) {
RegisterSubsystem(subsystem);
}
@@ -298,7 +299,7 @@ void CommandScheduler::UnregisterSubsystem(
}
void CommandScheduler::UnregisterSubsystem(
wpi::ArrayRef<Subsystem*> subsystems) {
wpi::span<Subsystem* const> subsystems) {
for (auto* subsystem : subsystems) {
UnregisterSubsystem(subsystem);
}
@@ -340,7 +341,7 @@ void CommandScheduler::Cancel(Command* command) {
}
}
void CommandScheduler::Cancel(wpi::ArrayRef<Command*> commands) {
void CommandScheduler::Cancel(wpi::span<Command* const> commands) {
for (auto command : commands) {
Cancel(command);
}
@@ -370,7 +371,7 @@ units::second_t CommandScheduler::TimeSinceScheduled(
}
}
bool CommandScheduler::IsScheduled(
wpi::ArrayRef<const Command*> commands) const {
wpi::span<const Command* const> commands) const {
for (auto command : commands) {
if (!IsScheduled(command)) {
return false;
@@ -444,8 +445,7 @@ void CommandScheduler::InitSendable(frc::SendableBuilder& builder) {
m_impl->scheduledCommands.end()) {
Cancel(command);
}
nt::NetworkTableEntry(cancelEntry)
.SetDoubleArray(wpi::ArrayRef<double>{});
nt::NetworkTableEntry(cancelEntry).SetDoubleArray({});
}
wpi::SmallVector<std::string, 8> names;

View File

@@ -21,7 +21,7 @@ FunctionalCommand::FunctionalCommand(std::function<void()> onInit,
std::function<void()> onExecute,
std::function<void(bool)> onEnd,
std::function<bool()> isFinished,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_onInit{std::move(onInit)},
m_onExecute{std::move(onExecute)},
m_onEnd{std::move(onEnd)},

View File

@@ -13,7 +13,7 @@ InstantCommand::InstantCommand(std::function<void()> toRun,
}
InstantCommand::InstantCommand(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_toRun{std::move(toRun)} {
AddRequirements(requirements);
}

View File

@@ -102,7 +102,7 @@ MecanumControllerCommand::MecanumControllerCommand(
std::function<void(units::volt_t, units::volt_t, units::volt_t,
units::volt_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_feedforward(feedforward),
@@ -139,7 +139,7 @@ MecanumControllerCommand::MecanumControllerCommand(
std::function<void(units::volt_t, units::volt_t, units::volt_t,
units::volt_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_feedforward(feedforward),
@@ -218,7 +218,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,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
@@ -239,7 +239,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,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),

View File

@@ -15,7 +15,7 @@ NotifierCommand::NotifierCommand(std::function<void()> toRun,
NotifierCommand::NotifierCommand(std::function<void()> toRun,
units::second_t period,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_toRun(toRun), m_notifier{std::move(toRun)}, m_period{period} {
AddRequirements(requirements);
}

View File

@@ -24,7 +24,7 @@ PIDCommand::PIDCommand(PIDController controller,
std::function<double()> measurementSource,
std::function<double()> setpointSource,
std::function<void(double)> useOutput,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_controller{std::move(controller)},
m_measurement{std::move(measurementSource)},
m_setpoint{std::move(setpointSource)},
@@ -43,7 +43,7 @@ PIDCommand::PIDCommand(PIDController controller,
PIDCommand::PIDCommand(PIDController controller,
std::function<double()> measurementSource,
double setpoint, std::function<void(double)> useOutput,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: PIDCommand(
controller, measurementSource, [setpoint] { return setpoint; },
useOutput, requirements) {}

View File

@@ -7,7 +7,7 @@
using namespace frc2;
PerpetualCommand::PerpetualCommand(std::unique_ptr<Command>&& command) {
if (!CommandGroupBase::RequireUngrouped(command)) {
if (!CommandGroupBase::RequireUngrouped(*command)) {
return;
}
m_command = std::move(command);

View File

@@ -6,10 +6,15 @@
using namespace frc2;
ProxyScheduleCommand::ProxyScheduleCommand(wpi::ArrayRef<Command*> toSchedule) {
ProxyScheduleCommand::ProxyScheduleCommand(
wpi::span<Command* const> toSchedule) {
SetInsert(m_toSchedule, toSchedule);
}
ProxyScheduleCommand::ProxyScheduleCommand(Command* toSchedule) {
SetInsert(m_toSchedule, {&toSchedule, 1});
}
void ProxyScheduleCommand::Initialize() {
for (auto* command : m_toSchedule) {
command->Schedule();

View File

@@ -39,7 +39,7 @@ RamseteCommand::RamseteCommand(
std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
frc2::PIDController leftController, frc2::PIDController rightController,
std::function<void(volt_t, volt_t)> output,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_controller(controller),
@@ -75,7 +75,7 @@ RamseteCommand::RamseteCommand(
frc::DifferentialDriveKinematics kinematics,
std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_controller(controller),

View File

@@ -13,7 +13,7 @@ RunCommand::RunCommand(std::function<void()> toRun,
}
RunCommand::RunCommand(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_toRun{std::move(toRun)} {
AddRequirements(requirements);
}

View File

@@ -6,10 +6,14 @@
using namespace frc2;
ScheduleCommand::ScheduleCommand(wpi::ArrayRef<Command*> toSchedule) {
ScheduleCommand::ScheduleCommand(wpi::span<Command* const> toSchedule) {
SetInsert(m_toSchedule, toSchedule);
}
ScheduleCommand::ScheduleCommand(Command* toSchedule) {
SetInsert(m_toSchedule, {&toSchedule, 1});
}
void ScheduleCommand::Initialize() {
for (auto command : m_toSchedule) {
command->Schedule();

View File

@@ -15,7 +15,7 @@ StartEndCommand::StartEndCommand(std::function<void()> onInit,
StartEndCommand::StartEndCommand(std::function<void()> onInit,
std::function<void()> onEnd,
wpi::ArrayRef<Subsystem*> requirements)
wpi::span<Subsystem* const> requirements)
: m_onInit{std::move(onInit)}, m_onEnd{std::move(onEnd)} {
AddRequirements(requirements);
}

View File

@@ -20,7 +20,7 @@ Button Button::WhenPressed(std::function<void()> toRun,
}
Button Button::WhenPressed(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
wpi::span<Subsystem* const> requirements) {
WhenActive(std::move(toRun), requirements);
return *this;
}
@@ -37,7 +37,7 @@ Button Button::WhileHeld(std::function<void()> toRun,
}
Button Button::WhileHeld(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
wpi::span<Subsystem* const> requirements) {
WhileActiveContinous(std::move(toRun), requirements);
return *this;
}
@@ -59,7 +59,7 @@ Button Button::WhenReleased(std::function<void()> toRun,
}
Button Button::WhenReleased(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
wpi::span<Subsystem* const> requirements) {
WhenInactive(std::move(toRun), requirements);
return *this;
}

View File

@@ -27,12 +27,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()));
return WhenActive(std::move(toRun),
{requirements.begin(), requirements.end()});
}
Trigger Trigger::WhenActive(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
wpi::span<Subsystem* const> requirements) {
return WhenActive(InstantCommand(std::move(toRun), requirements));
}
@@ -55,13 +55,12 @@ 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()));
return WhileActiveContinous(std::move(toRun),
{requirements.begin(), requirements.end()});
}
Trigger Trigger::WhileActiveContinous(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
Trigger Trigger::WhileActiveContinous(
std::function<void()> toRun, wpi::span<Subsystem* const> requirements) {
return WhileActiveContinous(InstantCommand(std::move(toRun), requirements));
}
@@ -97,12 +96,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()));
return WhenInactive(std::move(toRun),
{requirements.begin(), requirements.end()});
}
Trigger Trigger::WhenInactive(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
wpi::span<Subsystem* const> requirements) {
return WhenInactive(InstantCommand(std::move(toRun), requirements));
}