Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[wpilibcExamples] Update examples to CommandPtr #5988

Merged
merged 15 commits into from
Dec 4, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ void Robot::DisabledPeriodic() {}
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();

if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Schedule();
}
}
Expand All @@ -51,9 +51,9 @@ void Robot::TeleopInit() {
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
ncorrea210 marked this conversation as resolved.
Show resolved Hide resolved
m_autonomousCommand.reset();
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,6 @@ void RobotContainer::DisablePIDSubsystems() {
m_arm.Disable();
}

frc2::Command* RobotContainer::GetAutonomousCommand() {
return nullptr;
frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
return frc2::cmd::None();
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

#pragma once

#include <optional>

#include <frc/TimedRobot.h>
#include <frc2/command/Command.h>

Expand All @@ -24,7 +26,7 @@ class Robot : public frc::TimedRobot {
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
std::optional<frc2::CommandPtr> m_autonomousCommand;

RobotContainer m_container;
};
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#pragma once

#include <frc2/command/Command.h>
#include <frc2/command/CommandPtr.h>
#include <frc2/command/button/CommandXboxController.h>

#include "Constants.h"
Expand All @@ -28,7 +29,7 @@ class RobotContainer {
*/
void DisablePIDSubsystems();

frc2::Command* GetAutonomousCommand();
frc2::CommandPtr GetAutonomousCommand();

private:
// The driver's controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ void Robot::DisabledPeriodic() {}
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();

if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Schedule();
}
}
Expand All @@ -49,9 +49,9 @@ void Robot::TeleopInit() {
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
ncorrea210 marked this conversation as resolved.
Show resolved Hide resolved
m_autonomousCommand.reset();
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

#include "RobotContainer.h"

#include <frc2/command/Commands.h>
#include <units/angle.h>

RobotContainer::RobotContainer() {
Expand Down Expand Up @@ -34,6 +35,6 @@ void RobotContainer::ConfigureButtonBindings() {
.OnFalse(m_drive.SetMaxOutputCommand(1.0));
}

frc2::Command* RobotContainer::GetAutonomousCommand() {
return nullptr;
frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
return frc2::cmd::None();
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

#pragma once

#include <optional>

#include <frc/TimedRobot.h>
#include <frc2/command/Command.h>

Expand All @@ -24,7 +26,7 @@ class Robot : public frc::TimedRobot {
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
std::optional<frc2::CommandPtr> m_autonomousCommand;

RobotContainer m_container;
};
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#pragma once

#include <frc2/command/Command.h>
#include <frc2/command/CommandPtr.h>
#include <frc2/command/button/CommandXboxController.h>

#include "Constants.h"
Expand All @@ -24,7 +25,7 @@ class RobotContainer {
public:
RobotContainer();

frc2::Command* GetAutonomousCommand();
frc2::CommandPtr GetAutonomousCommand();

private:
// The driver's controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ void Robot::DisabledPeriodic() {}
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();

if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Schedule();
}
}
Expand All @@ -49,9 +49,9 @@ void Robot::TeleopInit() {
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
m_autonomousCommand.reset();
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

#include "RobotContainer.h"

#include <frc2/command/Commands.h>

#include "commands/DriveDistanceProfiled.h"

RobotContainer::RobotContainer() {
Expand Down Expand Up @@ -60,7 +62,7 @@ void RobotContainer::ConfigureButtonBindings() {
.WithTimeout(10_s));
}

frc2::Command* RobotContainer::GetAutonomousCommand() {
frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
// Runs the chosen command in autonomous
return nullptr;
return frc2::cmd::None();
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

#pragma once

#include <optional>

#include <frc/TimedRobot.h>
#include <frc2/command/Command.h>

Expand All @@ -24,7 +26,7 @@ class Robot : public frc::TimedRobot {
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
std::optional<frc2::CommandPtr> m_autonomousCommand;

RobotContainer m_container;
};
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class RobotContainer {
public:
RobotContainer();

frc2::Command* GetAutonomousCommand();
frc2::CommandPtr GetAutonomousCommand();

private:
// The driver's controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ void Robot::DisabledPeriodic() {}
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();

if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Schedule();
}
}
Expand All @@ -49,9 +49,9 @@ void Robot::TeleopInit() {
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
m_autonomousCommand.reset();
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ void RobotContainer::ConfigureButtonBindings() {
.OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {}));
}

frc2::Command* RobotContainer::GetAutonomousCommand() {
frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
// no auto
return nullptr;
return frc2::cmd::None();
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

#pragma once

#include <optional>

#include <frc/TimedRobot.h>
#include <frc2/command/Command.h>

Expand All @@ -24,7 +26,7 @@ class Robot : public frc::TimedRobot {
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
std::optional<frc2::CommandPtr> m_autonomousCommand;

RobotContainer m_container;
};
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
#include <frc/controller/PIDController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/CommandPtr.h>
#include <frc2/command/InstantCommand.h>

#include "Constants.h"
Expand All @@ -28,7 +29,7 @@ class RobotContainer {
public:
RobotContainer();

frc2::Command* GetAutonomousCommand();
frc2::CommandPtr GetAutonomousCommand();

private:
// The driver's controller
Expand All @@ -39,8 +40,5 @@ class RobotContainer {
// The robot's subsystems
DriveSubsystem m_drive;

// The chooser for the autonomous routines
frc::SendableChooser<frc2::Command*> m_chooser;

void ConfigureButtonBindings();
};
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ void Robot::DisabledPeriodic() {}
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();

if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Schedule();
}
}
Expand All @@ -49,9 +49,9 @@ void Robot::TeleopInit() {
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
m_autonomousCommand.reset();
}
}

Expand Down
Loading