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 filtering for buildAutoSendable() #726

Merged
merged 5 commits into from
Sep 23, 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
3 changes: 0 additions & 3 deletions .github/workflows/publish-docs.yml
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,6 @@ name: Build Documentation
on:
workflow_dispatch:

push:
branches: [main]

pull_request:

env:
Expand Down
75 changes: 75 additions & 0 deletions Writerside/topics/pplib-Build-an-Auto.md
Original file line number Diff line number Diff line change
Expand Up @@ -557,6 +557,8 @@ autos before they are shown on shuffle board
>
{style="warning"}

<tabs group="pplib-language">
<tab title="Java" group-key="java">

```java
public class RobotContainer {
Expand Down Expand Up @@ -586,4 +588,77 @@ 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() {
// ...

// For convenience a programmer could change this when going to competition.
bool isCompetition = true;

// Build an auto chooser. This will use frc2::cmd::None() as the default option.
// As an example, this will only show autos that start with "comp" while at
// competition as defined by the programmer
autoChooser = AutoBuilder::buildAutoChooser(
"", // If empty it will choose frc2::cmd::None()
[&isCompetition](const PathPlannerAuto *const autoCommand,
std::filesystem::path autoPath)
{
return isCompetition ? autoCommand->GetName().starts_with("comp") : true;
}
);

// Another option that allows you to specify the default auto by its name
/*
autoChooser = AutoBuilder::buildAutoChooser(
"autoDefault", // If filled it will choosen always, regardless of filter
[&isCompetition](const PathPlannerAuto *const autoCommand,
std::filesystem::path autoP)
{
return isCompetition ? autoCommand->GetName().starts_with("comp") : true;
}
);
*/

// Another option allows you to filter out current directories relative to pathplanner/auto deploy directory
// Allows only autos in directory deploy/pathplanner/autos/comp
/*
autoChooser = AutoBuilder::buildAutoChooser(
"",
[&isCompetition](const PathPlannerAuto *const autoCommand,
std::filesystem::path autoPath)
{
return isCompetition ? autoPath.compare("comp") > 0 : true;
}
);
*/

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>
</tabs>

</snippet>
Original file line number Diff line number Diff line change
@@ -1,13 +1,11 @@
#include "pathplanner/lib/auto/AutoBuilder.h"
#include "pathplanner/lib/commands/PathPlannerAuto.h"
#include "pathplanner/lib/commands/FollowPathCommand.h"
#include "pathplanner/lib/commands/PathfindingCommand.h"
#include "pathplanner/lib/commands/PathfindThenFollowPath.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>

Expand All @@ -19,7 +17,9 @@ std::function<void(frc::Pose2d)> AutoBuilder::m_resetPose;
std::function<bool()> AutoBuilder::m_shouldFlipPath;
bool AutoBuilder::m_isHolonomic = false;

std::vector<frc2::CommandPtr> AutoBuilder::m_autoCommands;
bool AutoBuilder::m_commandRefsGeneratedForSendable = false;
frc2::CommandPtr AutoBuilder::m_noneCommand = frc2::cmd::None();
std::map<std::filesystem::path, frc2::CommandPtr> AutoBuilder::m_autoCommands;

bool AutoBuilder::m_pathfindingConfigured = false;
std::function<
Expand Down Expand Up @@ -143,36 +143,69 @@ frc2::CommandPtr AutoBuilder::pathfindThenFollowPath(
pathfindingConstraints);
}

void AutoBuilder::regenerateSendableReferences() {
std::vector < std::filesystem::path > autoPathFilepaths = getAllAutoPaths();

for (std::filesystem::path path : autoPathFilepaths) {
// A command which is an auto that come from a path
m_autoCommands.insert_or_assign(path,
buildAuto(path.replace_extension("").string()));
}
}

frc::SendableChooser<frc2::Command*> AutoBuilder::buildAutoChooser(
std::string defaultAutoName) {
std::string defaultAutoName,
std::function<bool(const PathPlannerAuto* const, std::filesystem::path)> filter) {
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;
if (!m_commandRefsGeneratedForSendable) {
regenerateSendableReferences();
m_commandRefsGeneratedForSendable = true;
}

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());
frc::SendableChooser<frc2::Command*> sendableChooser;
bool defaultSelected = false;

for (const std::pair<const std::filesystem::path, frc2::CommandPtr> &entry : m_autoCommands) {
std::string autoName = entry.first.stem().string();

// Found the default for sendableChooser
if (defaultAutoName == autoName) {
sendableChooser.SetDefaultOption(autoName, entry.second.get());
defaultSelected = true;
} else if (filter(
dynamic_cast<const PathPlannerAuto* const >(entry.second.get()),
entry.first)) {
sendableChooser.AddOption(autoName, entry.second.get());
}
}

if (!foundDefaultOption) {
AutoBuilder::m_autoCommands.emplace_back(frc2::cmd::None());
chooser.SetDefaultOption("None", m_autoCommands.back().get());
// None is the default
if (!defaultSelected || defaultAutoName == "") {
sendableChooser.SetDefaultOption("None", m_noneCommand.get());
}
// None is just there, extra precaution for programmers
else {
sendableChooser.AddOption("None", m_noneCommand.get());
}

return chooser;
return sendableChooser;
}

std::vector<std::string> AutoBuilder::getAllAutoNames() {
std::vector < std::string > autoNames;

for (const std::filesystem::path &path : getAllAutoPaths()) {
autoNames.push_back(path.stem().string());
}

return autoNames;
}

std::vector<std::filesystem::path> AutoBuilder::getAllAutoPaths() {
std::filesystem::path deployPath = frc::filesystem::GetDeployDirectory();
std::filesystem::path autosPath = deployPath / "pathplanner/autos";

Expand All @@ -183,17 +216,16 @@ std::vector<std::string> AutoBuilder::getAllAutoNames() {
return {};
}

std::vector < std::string > autoPathNames;
std::vector < std::filesystem::path > 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") {
for (std::filesystem::directory_entry const &entry : std::filesystem::recursive_directory_iterator {
autosPath,
std::filesystem::directory_options::skip_permission_denied }) {
if (!entry.is_regular_file()
|| entry.path().extension().string() != ".auto") {
continue;
}
autoPathNames.emplace_back(entry.path().stem().string());
autoPathNames.emplace_back(entry.path().lexically_relative(autosPath));
}

return autoPathNames;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,15 @@
#include <frc/kinematics/ChassisSpeeds.h>
#include <frc/controller/RamseteController.h>
#include <vector>
#include <map>
#include <frc2/command/Command.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <memory>
#include <wpi/json.h>
#include <wpi/array.h>
#include <string>
#include "pathplanner/lib/path/PathPlannerPath.h"
#include "pathplanner/lib/commands/PathPlannerAuto.h"
#include "pathplanner/lib/config/RobotConfig.h"
#include "pathplanner/lib/controllers/PathFollowingController.h"

Expand Down Expand Up @@ -149,31 +151,58 @@ class AutoBuilder {
PathConstraints pathfindingConstraints);

/**
* Create and populate a sendable chooser with all PathPlannerAutos in the project
* Modifies the existing references that buildAutoChooser returns in SendableChooser to the most recent in the pathplanner/auto deploy directory
*
* Adds new auto paths from the pathplanner/auto deploy directory however doesn't remove autos already previously loaded
*/

static void regenerateSendableReferences();

/**
* Create and populate a sendable chooser with all PathPlannerAutos in the project in pathplanner/auto deploy directory (recurively)
*
* @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()
* frc2::cmd::None(), defaultAutoName doesn't get filter out and always is in final sendable chooser
* @param filter Function which filters the auto commands out, returning true allows the command to be uploaded to sendable chooser
* while returning false prevents it from being added.
* First param: autoCommand, pointer to PathPlannerAuto command which was generated
* Second param: autoPath, path to the autoCommand relative to pathplanner/auto deploy directory with extension ".auto"
* @return SendableChooser populated with all autos
*/
static frc::SendableChooser<frc2::Command*> buildAutoChooser(
std::string defaultAutoName = "");
std::string defaultAutoName = "",
std::function<
bool(const PathPlannerAuto* const, std::filesystem::path)> filter =
[](const PathPlannerAuto *const autoCommand,
std::filesystem::path autoPath) {
return true;
});

/**
* Get a vector of all auto names in the project
* Get a vector of all auto names in the pathplanner/auto deploy directory (recurively)
*
* @return vector of all auto names
* @return Vector of strings containing all auto names
*/
static std::vector<std::string> getAllAutoNames();

/**
* Get a vector of all auto paths in the pathplanner/auto deploy directory (recurively)
*
* @return Vector of paths relative to autos deploy directory
*/
static std::vector<std::filesystem::path> getAllAutoPaths();

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

static std::vector<frc2::CommandPtr> m_autoCommands;
static bool m_commandRefsGeneratedForSendable;
static frc2::CommandPtr m_noneCommand;
static std::map<std::filesystem::path, frc2::CommandPtr> m_autoCommands;

static bool m_pathfindingConfigured;
static std::function<
Expand Down