diff --git a/Writerside/topics/pplib-Build-an-Auto.md b/Writerside/topics/pplib-Build-an-Auto.md
index d4d7f4d8..f09f5bfc 100644
--- a/Writerside/topics/pplib-Build-an-Auto.md
+++ b/Writerside/topics/pplib-Build-an-Auto.md
@@ -440,12 +440,6 @@ class RobotContainer:
## Create a SendableChooser with all autos in project
-> **Note**
->
-> This feature is only available in the Java and Python versions of PathPlannerLib
->
-{style="note"}
-
After configuring the AutoBuilder, you have the option to build a SendableChooser that is automatically populated with
every auto in the project.
@@ -485,6 +479,41 @@ public class RobotContainer {
}
```
+
+
+
+```C++
+#include
+#include
+#include
+#include
+#include
+
+using namespace pathplanner;
+
+RobotContainer::RobotContainer() {
+ // ...
+
+ // Build an auto chooser. This will use frc2::cmd::None() as the default option.
+ autoChooser = AutoBuilder::buildAutoChooser();
+
+ // Another option that allows you to specify the default auto by its name
+ // autoChooser = AutoBuilder::buildAutoChooser("My Default Auto");
+
+ frc::SmartDashboard::PutData("Auto Chooser", &autoChooser);
+}
+
+frc2::Command* RobotContainer::getAutonomousCommand() {
+ // Returns a frc2::Command* that is freed at program termination
+ return autoChooser.GetSelected();
+}
+
+frc2::CommandPtr RobotContainer::getAutonomousCommand() {
+ // Returns a copy that is freed after reference is lost
+ return frc2::CommandPtr(std::make_unique(*autoChooser.GetSelected()));
+}
+```
+
diff --git a/pathplannerlib/src/main/native/cpp/pathplanner/lib/auto/AutoBuilder.cpp b/pathplannerlib/src/main/native/cpp/pathplanner/lib/auto/AutoBuilder.cpp
index 046853af..860890b8 100644
--- a/pathplannerlib/src/main/native/cpp/pathplanner/lib/auto/AutoBuilder.cpp
+++ b/pathplannerlib/src/main/native/cpp/pathplanner/lib/auto/AutoBuilder.cpp
@@ -9,10 +9,13 @@
#include "pathplanner/lib/commands/PathfindThenFollowPathRamsete.h"
#include "pathplanner/lib/commands/PathfindLTV.h"
#include "pathplanner/lib/commands/PathfindThenFollowPathLTV.h"
+#include "pathplanner/lib/commands/PathPlannerAuto.h"
#include "pathplanner/lib/auto/CommandUtil.h"
#include
#include
#include
+#include
+#include
#include
using namespace pathplanner;
@@ -23,6 +26,8 @@ std::function AutoBuilder::m_getPose;
std::function AutoBuilder::m_resetPose;
std::function AutoBuilder::m_shouldFlipPath;
+std::vector AutoBuilder::m_autoCommands;
+
bool AutoBuilder::m_pathfindingConfigured = false;
std::function<
frc2::CommandPtr(frc::Pose2d, PathConstraints,
@@ -352,3 +357,59 @@ frc2::CommandPtr AutoBuilder::pathfindThenFollowPath(
return m_pathfindThenFollowPathCommandBuilder(goalPath,
pathfindingConstraints, rotationDelayDistance);
}
+
+frc::SendableChooser AutoBuilder::buildAutoChooser(
+ std::string defaultAutoName) {
+ if (!m_configured) {
+ throw std::runtime_error(
+ "AutoBuilder was not configured before attempting to build an auto chooser");
+ }
+
+ frc::SendableChooser chooser;
+ bool foundDefaultOption = false;
+
+ for (std::string const &entry : getAllAutoNames()) {
+ AutoBuilder::m_autoCommands.emplace_back(
+ pathplanner::PathPlannerAuto(entry).ToPtr());
+ if (defaultAutoName != "" && entry == defaultAutoName) {
+ foundDefaultOption = true;
+ chooser.SetDefaultOption(entry, m_autoCommands.back().get());
+ } else {
+ chooser.AddOption(entry, m_autoCommands.back().get());
+ }
+ }
+
+ if (!foundDefaultOption) {
+ AutoBuilder::m_autoCommands.emplace_back(frc2::cmd::None());
+ chooser.SetDefaultOption("None", m_autoCommands.back().get());
+ }
+
+ return chooser;
+}
+
+std::vector AutoBuilder::getAllAutoNames() {
+ std::filesystem::path deployPath = frc::filesystem::GetDeployDirectory();
+ std::filesystem::path autosPath = deployPath / "pathplanner/autos";
+
+ if (!std::filesystem::directory_entry { autosPath }.exists()) {
+ FRC_ReportError(frc::err::Error,
+ "AutoBuilder could not locate the pathplanner autos directory");
+
+ return {};
+ }
+
+ std::vector < std::string > autoPathNames;
+
+ for (std::filesystem::directory_entry const &entry : std::filesystem::directory_iterator {
+ autosPath }) {
+ if (!entry.is_regular_file()) {
+ continue;
+ }
+ if (entry.path().extension().string() != ".auto") {
+ continue;
+ }
+ autoPathNames.emplace_back(entry.path().stem().string());
+ }
+
+ return autoPathNames;
+}
diff --git a/pathplannerlib/src/main/native/include/pathplanner/lib/auto/AutoBuilder.h b/pathplannerlib/src/main/native/include/pathplanner/lib/auto/AutoBuilder.h
index 8cc03918..b4b73157 100644
--- a/pathplannerlib/src/main/native/include/pathplanner/lib/auto/AutoBuilder.h
+++ b/pathplannerlib/src/main/native/include/pathplanner/lib/auto/AutoBuilder.h
@@ -6,6 +6,9 @@
#include
#include
#include
+#include
+#include
+#include
#include
#include
#include
@@ -252,6 +255,24 @@ class AutoBuilder {
PathConstraints pathfindingConstraints,
units::meter_t rotationDelayDistance = 0_m);
+ /**
+ * Create and populate a sendable chooser with all PathPlannerAutos in the project
+ *
+ * @param defaultAutoName The name of the auto that should be the default option. If this is an
+ * empty string, or if an auto with the given name does not exist, the default option will be
+ * frc2::cmd::None()
+ * @return SendableChooser populated with all autos
+ */
+ static frc::SendableChooser buildAutoChooser(
+ std::string defaultAutoName = "");
+
+ /**
+ * Get a vector of all auto names in the project
+ *
+ * @return vector of all auto names
+ */
+ static std::vector getAllAutoNames();
+
private:
static bool m_configured;
static std::function)> m_pathFollowingCommandBuilder;
@@ -259,6 +280,8 @@ class AutoBuilder {
static std::function m_resetPose;
static std::function m_shouldFlipPath;
+ static std::vector m_autoCommands;
+
static bool m_pathfindingConfigured;
static std::function<
frc2::CommandPtr(frc::Pose2d, PathConstraints,