Skip to content

Commit

Permalink
remove use of ToPtr
Browse files Browse the repository at this point in the history
  • Loading branch information
Starlight220 committed Dec 24, 2023
1 parent 727e070 commit 9ca257d
Show file tree
Hide file tree
Showing 16 changed files with 43 additions and 90 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -235,7 +235,7 @@ CommandPtr CommandPtr::WithName(std::string_view name) && {
AssertValid();
WrapperCommand wrapper{std::move(m_ptr)};
wrapper.SetName(name);
return std::move(wrapper).ToPtr();
return std::move(wrapper);
}

Command* CommandPtr::get() const& {
Expand Down
32 changes: 16 additions & 16 deletions wpilibNewCommands/src/main/native/cpp/frc2/command/Commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ using namespace frc2;
// Factories

CommandPtr cmd::None() {
return InstantCommand().ToPtr();
return InstantCommand();
}

CommandPtr cmd::Idle(Requirements requirements) {
Expand All @@ -32,11 +32,11 @@ CommandPtr cmd::Idle(Requirements requirements) {

CommandPtr cmd::RunOnce(std::function<void()> action,
Requirements requirements) {
return InstantCommand(std::move(action), requirements).ToPtr();
return InstantCommand(std::move(action), requirements);
}

CommandPtr cmd::Run(std::function<void()> action, Requirements requirements) {
return RunCommand(std::move(action), requirements).ToPtr();
return RunCommand(std::move(action), requirements);
}

CommandPtr cmd::StartEnd(std::function<void()> start, std::function<void()> end,
Expand All @@ -45,52 +45,52 @@ CommandPtr cmd::StartEnd(std::function<void()> start, std::function<void()> end,
std::move(start), [] {},
[end = std::move(end)](bool interrupted) { end(); },
[] { return false; }, requirements)
.ToPtr();
;
}

CommandPtr cmd::RunEnd(std::function<void()> run, std::function<void()> end,
Requirements requirements) {
return FunctionalCommand([] {}, std::move(run),
[end = std::move(end)](bool interrupted) { end(); },
[] { return false; }, requirements)
.ToPtr();
;
}

CommandPtr cmd::Print(std::string_view msg) {
return PrintCommand(msg).ToPtr();
return PrintCommand(msg);
}

CommandPtr cmd::DeferredProxy(wpi::unique_function<Command*()> supplier) {
return ProxyCommand(std::move(supplier)).ToPtr();
return ProxyCommand(std::move(supplier));
}

CommandPtr cmd::DeferredProxy(wpi::unique_function<CommandPtr()> supplier) {
return ProxyCommand(std::move(supplier)).ToPtr();
return ProxyCommand(std::move(supplier));
}

CommandPtr cmd::Wait(units::second_t duration) {
return WaitCommand(duration).ToPtr();
return WaitCommand(duration);
}

CommandPtr cmd::WaitUntil(std::function<bool()> condition) {
return WaitUntilCommand(condition).ToPtr();
return WaitUntilCommand(condition);
}

CommandPtr cmd::Either(CommandPtr&& onTrue, CommandPtr&& onFalse,
std::function<bool()> selector) {
return ConditionalCommand(std::move(onTrue).Unwrap(),
std::move(onFalse).Unwrap(), std::move(selector))
.ToPtr();
;
}

CommandPtr cmd::Defer(wpi::unique_function<CommandPtr()> supplier,
Requirements requirements) {
return DeferredCommand(std::move(supplier), requirements).ToPtr();
return DeferredCommand(std::move(supplier), requirements);
}

CommandPtr cmd::Sequence(std::vector<CommandPtr>&& commands) {
return SequentialCommandGroup(CommandPtr::UnwrapVector(std::move(commands)))
.ToPtr();
;
}

CommandPtr cmd::RepeatingSequence(std::vector<CommandPtr>&& commands) {
Expand All @@ -99,17 +99,17 @@ CommandPtr cmd::RepeatingSequence(std::vector<CommandPtr>&& commands) {

CommandPtr cmd::Parallel(std::vector<CommandPtr>&& commands) {
return ParallelCommandGroup(CommandPtr::UnwrapVector(std::move(commands)))
.ToPtr();
;
}

CommandPtr cmd::Race(std::vector<CommandPtr>&& commands) {
return ParallelRaceGroup(CommandPtr::UnwrapVector(std::move(commands)))
.ToPtr();
;
}

CommandPtr cmd::Deadline(CommandPtr&& deadline,
std::vector<CommandPtr>&& others) {
return ParallelDeadlineGroup(std::move(deadline).Unwrap(),
CommandPtr::UnwrapVector(std::move(others)))
.ToPtr();
;
}
Original file line number Diff line number Diff line change
Expand Up @@ -169,27 +169,6 @@ class CommandScheduler final : public wpi::Sendable,
*/
void UnregisterAllSubsystems();

/**
* Sets the default command for a subsystem. Registers that subsystem if it
* is not already registered. Default commands will run whenever there is no
* other command currently scheduled that requires the subsystem. Default
* commands should be written to never end (i.e. their IsFinished() method
* should return false), as they would simply be re-scheduled if they do.
* Default commands must also require their subsystem.
*
* @param subsystem the subsystem whose default command will be set
* @param defaultCommand the default command to associate with the subsystem
*/
template <std::derived_from<Command> T>
void SetDefaultCommand(Subsystem* subsystem, T&& defaultCommand) {
if (!defaultCommand.HasRequirement(subsystem)) {
throw FRC_MakeError(frc::err::CommandIllegalUse,
"Default commands must require their subsystem!");
}
SetDefaultCommandImpl(subsystem, std::make_unique<std::decay_t<T>>(
std::forward<T>(defaultCommand)));
}

/**
* Sets the default command for a subsystem. Registers that subsystem if it
* is not already registered. Default commands will run whenever there is no
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ CommandPtr Select(std::function<Key()> selector,
((void)vec.emplace_back(commands.first, std::move(commands.second).Unwrap()),
...);

return SelectCommand(std::move(selector), std::move(vec)).ToPtr();
return SelectCommand(std::move(selector), std::move(vec));
}

/**
Expand Down
15 changes: 0 additions & 15 deletions wpilibNewCommands/src/main/native/include/frc2/command/Subsystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,21 +67,6 @@ class Subsystem {
*/
virtual std::string GetName() const;

/**
* Sets the default Command of the subsystem. The default command will be
* automatically scheduled when no other commands are scheduled that require
* the subsystem. Default commands should generally not end on their own, i.e.
* their IsFinished() method should always return false. Will automatically
* register this subsystem with the CommandScheduler.
*
* @param defaultCommand the default command to associate with this subsystem
*/
template <std::derived_from<Command> T>
void SetDefaultCommand(T&& defaultCommand) {
CommandScheduler::GetInstance().SetDefaultCommand(
this, std::forward<T>(defaultCommand));
}

/**
* Sets the default Command of the subsystem. The default command will be
* automatically scheduled when no other commands are scheduled that require
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,7 @@ class WrapperCommand : public CommandHelper<Command, WrapperCommand> {
* @param command the command being wrapped. Trying to directly schedule this
* command or add it to a group will throw an exception.
*/
template <std::derived_from<Command> T>
// NOLINTNEXTLINE(bugprone-forwarding-reference-overload)
explicit WrapperCommand(T&& command)
explicit WrapperCommand(CommandPtr&& command)
: WrapperCommand(

Check failure on line 44 in wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h

View workflow job for this annotation

GitHub Actions / Build - Windows

'frc2::WrapperCommand::WrapperCommand': no appropriate default constructor available
std::make_unique<std::decay_t<T>>(std::forward<T>(command))) {}

Check failure on line 45 in wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h

View workflow job for this annotation

GitHub Actions / Build - Windows

'T': undeclared identifier

Check failure on line 45 in wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h

View workflow job for this annotation

GitHub Actions / Build - Windows

'std::decay_t': 'T' is not a valid template type argument for parameter '_Ty'

Check failure on line 45 in wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h

View workflow job for this annotation

GitHub Actions / Build - Windows

'T': undeclared identifier

Check failure on line 45 in wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h

View workflow job for this annotation

GitHub Actions / Build - Windows

'std::forward': no matching overloaded function found

Check failure on line 45 in wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h

View workflow job for this annotation

GitHub Actions / Build - Windows

'std::make_unique': no matching overloaded function found

Check failure on line 45 in wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h

View workflow job for this annotation

GitHub Actions / Build - Windows

'T': undeclared identifier

Check failure on line 45 in wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h

View workflow job for this annotation

GitHub Actions / Build - Windows

'std::decay_t': 'T' is not a valid template type argument for parameter '_Ty'

Check failure on line 45 in wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h

View workflow job for this annotation

GitHub Actions / Build - Windows

'T': undeclared identifier

Check failure on line 45 in wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h

View workflow job for this annotation

GitHub Actions / Build - Windows

'std::forward': no matching overloaded function found

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,7 @@ TEST_P(DeferredFunctionsTest, DeferredFunctions) {
[&] {
isFinishedCount++;
return finished;
}}
.ToPtr();
}};
},
{}};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,6 @@ void RobotContainer::ConfigureButtonBindings() {
[] { return frc::TrapezoidProfile<units::meters>::State{}; },
// Require the drive
{&m_drive})
// Convert to CommandPtr
.ToPtr()
.BeforeStarting(
frc2::cmd::RunOnce([this]() { m_drive.ResetEncoders(); }, {}))
.WithTimeout(10_s));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,19 +33,18 @@ RobotContainer::RobotContainer()
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
frc2::JoystickButton(&m_joy, 5).OnTrue(
SetElevatorSetpoint(0.25, m_elevator).ToPtr());
frc2::JoystickButton(&m_joy, 6).OnTrue(CloseClaw(m_claw).ToPtr());
SetElevatorSetpoint(0.25, m_elevator));
frc2::JoystickButton(&m_joy, 6).OnTrue(CloseClaw(m_claw));
frc2::JoystickButton(&m_joy, 7).OnTrue(
SetElevatorSetpoint(0.0, m_elevator).ToPtr());
frc2::JoystickButton(&m_joy, 8).OnTrue(OpenClaw(m_claw).ToPtr());
SetElevatorSetpoint(0.0, m_elevator));
frc2::JoystickButton(&m_joy, 8).OnTrue(OpenClaw(m_claw));
frc2::JoystickButton(&m_joy, 9).OnTrue(
Autonomous(m_claw, m_wrist, m_elevator, m_drivetrain).ToPtr());
Autonomous(m_claw, m_wrist, m_elevator, m_drivetrain));
frc2::JoystickButton(&m_joy, 10)
.OnTrue(Pickup(m_claw, m_wrist, m_elevator).ToPtr());
frc2::JoystickButton(&m_joy, 11)
.OnTrue(Place(m_claw, m_wrist, m_elevator).ToPtr());
.OnTrue(Pickup(m_claw, m_wrist, m_elevator));
frc2::JoystickButton(&m_joy, 11).OnTrue(Place(m_claw, m_wrist, m_elevator));
frc2::JoystickButton(&m_joy, 12)
.OnTrue(PrepareToPickup(m_claw, m_wrist, m_elevator).ToPtr());
.OnTrue(PrepareToPickup(m_claw, m_wrist, m_elevator));
}

frc2::Command* RobotContainer::GetAutonomousCommand() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ void RobotContainer::ConfigureButtonBindings() {
},
// Require the robot drive
{&m_drive})
.ToPtr());
);

// Turn to 90 degrees when the 'Cross' button is pressed
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kCross)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ frc2::CommandPtr autos::SimpleAuto(DriveSubsystem* drive) {
},
// Requires the drive subsystem
{drive})
.ToPtr();
;
}

frc2::CommandPtr autos::ComplexAuto(DriveSubsystem* drive,
Expand All @@ -49,7 +49,7 @@ frc2::CommandPtr autos::ComplexAuto(DriveSubsystem* drive,
},
// Requires the drive subsystem
{drive})
.ToPtr(),
,
// Release the hatch
hatch->ReleaseHatchCommand(),
// Drive backward the specified distance
Expand All @@ -69,5 +69,5 @@ frc2::CommandPtr autos::ComplexAuto(DriveSubsystem* drive,
},
// Requires the drive subsystem
{drive})
.ToPtr());
);
}
Original file line number Diff line number Diff line change
Expand Up @@ -68,14 +68,14 @@ void RobotContainer::ConfigureButtonBindings() {

// Grab the hatch when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.OnTrue(GrabHatch(&m_hatch).ToPtr());
.OnTrue(GrabHatch(&m_hatch));
// Release the hatch when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
.OnTrue(ReleaseHatch(&m_hatch).ToPtr());
.OnTrue(ReleaseHatch(&m_hatch));
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.WhileTrue(HalveDriveSpeed(&m_drive).ToPtr());
.WhileTrue(HalveDriveSpeed(&m_drive));
}

frc2::Command* RobotContainer::GetAutonomousCommand() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,9 +103,7 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
m_drive.SetMotorControllersVolts(frontLeft, rearLeft, frontRight,
rearRight);
},

{&m_drive})
.ToPtr();
{&m_drive});

// Reset odometry to the initial pose of the trajectory, run path following
// command, then stop at the end.
Expand All @@ -114,9 +112,7 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
[this, &exampleTrajectory]() {
m_drive.ResetOdometry(exampleTrajectory.InitialPose());
},
{})
.ToPtr(),
{}),
std::move(mecanumControllerCommand),
frc2::InstantCommand([this]() { m_drive.Drive(0, 0, 0, false); }, {})
.ToPtr());
frc2::InstantCommand([this]() { m_drive.Drive(0, 0, 0, false); }, {}));
}
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
[this](auto moduleStates) { m_drive.SetModuleStates(moduleStates); },

{&m_drive})
.ToPtr();
;

// Reset odometry to the initial pose of the trajectory, run path following
// command, then stop at the end.
Expand All @@ -96,10 +96,9 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
[this, &exampleTrajectory]() {
m_drive.ResetOdometry(exampleTrajectory.InitialPose());
},
{})
.ToPtr(),
{}),
std::move(swerveControllerCommand),
frc2::InstantCommand(
[this] { m_drive.Drive(0_mps, 0_mps, 0_rad_per_s, false); }, {})
.ToPtr());
);
}
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ void RobotContainer::ConfigureBindings() {
// Schedule `ExampleCommand` when `exampleCondition` changes to `true`
frc2::Trigger([this] {
return m_subsystem.ExampleCondition();
}).OnTrue(ExampleCommand(&m_subsystem).ToPtr());
}).OnTrue(ExampleCommand(&m_subsystem));

// Schedule `ExampleMethodCommand` when the Xbox controller's B button is
// pressed, cancelling on release.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,5 +10,5 @@

frc2::CommandPtr autos::ExampleAuto(ExampleSubsystem* subsystem) {
return frc2::cmd::Sequence(subsystem->ExampleMethodCommand(),
ExampleCommand(subsystem).ToPtr());
ExampleCommand(subsystem));
}

0 comments on commit 9ca257d

Please sign in to comment.