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

Added buildAutoChooser to C++ lib #670

Merged
merged 8 commits into from
Apr 4, 2024
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
41 changes: 35 additions & 6 deletions Writerside/topics/pplib-Build-an-Auto.md
Original file line number Diff line number Diff line change
Expand Up @@ -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.

Expand Down Expand Up @@ -485,6 +479,41 @@ public class RobotContainer {
}
```

</tab>
<tab title="C++" group-key="cpp">

```C++
#include <pathplanner/lib/auto/AutoBuilder.h>
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandPtr.h>
#include <frc2/command/Command.h>
#include <memory>

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<frc2::Command>(*autoChooser.GetSelected()));
}
```

</tab>
<tab title="Python" group-key="python">

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <stdexcept>
#include <frc2/command/Commands.h>
#include <frc/Filesystem.h>
#include <filesystem>
#include <optional>
#include <wpi/MemoryBuffer.h>

using namespace pathplanner;
Expand All @@ -23,6 +26,8 @@ std::function<frc::Pose2d()> AutoBuilder::m_getPose;
std::function<void(frc::Pose2d)> AutoBuilder::m_resetPose;
std::function<bool()> AutoBuilder::m_shouldFlipPath;

std::vector<frc2::CommandPtr> AutoBuilder::m_autoCommands;

bool AutoBuilder::m_pathfindingConfigured = false;
std::function<
frc2::CommandPtr(frc::Pose2d, PathConstraints,
Expand Down Expand Up @@ -352,3 +357,59 @@ frc2::CommandPtr AutoBuilder::pathfindThenFollowPath(
return m_pathfindThenFollowPathCommandBuilder(goalPath,
pathfindingConstraints, rotationDelayDistance);
}

frc::SendableChooser<frc2::Command*> 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<frc2::Command*> 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<std::string> 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;
}
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,9 @@
#include <frc/geometry/Pose2d.h>
#include <frc/kinematics/ChassisSpeeds.h>
#include <frc/controller/RamseteController.h>
#include <vector>
#include <frc2/command/Command.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <memory>
#include <wpi/json.h>
#include <wpi/array.h>
Expand Down Expand Up @@ -252,13 +255,33 @@ 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<frc2::Command*> buildAutoChooser(
std::string defaultAutoName = "");

/**
* Get a vector of all auto names in the project
*
* @return vector of all auto names
*/
static std::vector<std::string> getAllAutoNames();

private:
static bool m_configured;
static std::function<frc2::CommandPtr(std::shared_ptr<PathPlannerPath>)> m_pathFollowingCommandBuilder;
static std::function<frc::Pose2d()> m_getPose;
static std::function<void(frc::Pose2d)> m_resetPose;
static std::function<bool()> m_shouldFlipPath;

static std::vector<frc2::CommandPtr> m_autoCommands;

static bool m_pathfindingConfigured;
static std::function<
frc2::CommandPtr(frc::Pose2d, PathConstraints,
Expand Down
Loading