+
+
+
4#include <frc2/command/CommandPtr.h>
+
5#include <frc/geometry/Pose2d.h>
+
6#include <frc/kinematics/ChassisSpeeds.h>
+
7#include <frc/controller/RamseteController.h>
+
+
+
+
+
12#include "pathplanner/lib/path/PathPlannerPath.h"
+
13#include "pathplanner/lib/util/HolonomicPathFollowerConfig.h"
+
14#include "pathplanner/lib/util/ReplanningConfig.h"
+
+
16namespace pathplanner {
+
+
+
+
31 std::function<
void(frc::Pose2d)> resetPose,
+
32 std::function<frc::ChassisSpeeds()> robotRelativeSpeedsSupplier,
+
33 std::function<
void(frc::ChassisSpeeds)> robotRelativeOutput,
+
+
35 frc2::Subsystem *driveSubsystem);
+
+
+
48 std::function<
void(frc::Pose2d)> resetPose,
+
49 std::function<frc::ChassisSpeeds()> speedsSupplier,
+
50 std::function<
void(frc::ChassisSpeeds)> output,
+
+
+
+
68 std::function<
void(frc::Pose2d)> resetPose,
+
69 std::function<frc::ChassisSpeeds()> speedsSupplier,
+
70 std::function<
void(frc::ChassisSpeeds)> output,
+
71 units::unit_t<frc::RamseteController::b_unit> b,
+
72 units::unit_t<frc::RamseteController::zeta_unit> zeta,
+
+
+
89 static void configureLTV(std::function<frc::Pose2d()> poseSupplier,
+
90 std::function<
void(frc::Pose2d)> resetPose,
+
91 std::function<frc::ChassisSpeeds()> speedsSupplier,
+
92 std::function<
void(frc::ChassisSpeeds)> output,
+
93 const wpi::array<double, 3> &Qelms,
+
94 const wpi::array<double, 2> &Relms, units::second_t dt,
+
+
+
109 static void configureLTV(std::function<frc::Pose2d()> poseSupplier,
+
110 std::function<
void(frc::Pose2d)> resetPose,
+
111 std::function<frc::ChassisSpeeds()> speedsSupplier,
+
112 std::function<
void(frc::ChassisSpeeds)> output, units::second_t dt,
+
+
+
+
123 std::function<frc2::CommandPtr(std::shared_ptr<PathPlannerPath>)> pathFollowingCommandBuilder,
+
124 std::function<frc::Pose2d()> poseSupplier,
+
125 std::function<
void(frc::Pose2d)> resetPose);
+
+
+
+
+
+
+
143 std::shared_ptr<PathPlannerPath> path);
+
+
151 static frc2::CommandPtr
buildAuto(std::string autoName);
+
+
+
+
161 static frc::Pose2d getStartingPoseFromJson(
const wpi::json &json);
+
+
+
+
176 0_mps, units::meter_t rotationDelayDistance = 0_m);
+
+
+
189 std::shared_ptr<PathPlannerPath> goalPath,
+
+
191 units::meter_t rotationDelayDistance = 0_m);
+
+
+
194 static bool m_configured;
+
195 static std::function<frc2::CommandPtr(std::shared_ptr<PathPlannerPath>)> m_pathFollowingCommandBuilder;
+
196 static std::function<frc::Pose2d()> m_getPose;
+
197 static std::function<void(frc::Pose2d)> m_resetPose;
+
+
199 static bool m_pathfindingConfigured;
+
200 static std::function<
+
+
202 units::meters_per_second_t, units::meter_t)> m_pathfindToPoseCommandBuilder;
+
203 static std::function<
+
+
205 units::meter_t)> m_pathfindThenFollowPathCommandBuilder;
+
+
+
Definition: AutoBuilder.h:17
+
static frc2::CommandPtr followPathWithEvents(std::shared_ptr< PathPlannerPath > path)
Definition: AutoBuilder.cpp:254
+
static void configureRamsete(std::function< frc::Pose2d()> poseSupplier, std::function< void(frc::Pose2d)> resetPose, std::function< frc::ChassisSpeeds()> speedsSupplier, std::function< void(frc::ChassisSpeeds)> output, ReplanningConfig replanningConfig, frc2::Subsystem *driveSubsystem)
Definition: AutoBuilder.cpp:74
+
static void configureHolonomic(std::function< frc::Pose2d()> poseSupplier, std::function< void(frc::Pose2d)> resetPose, std::function< frc::ChassisSpeeds()> robotRelativeSpeedsSupplier, std::function< void(frc::ChassisSpeeds)> robotRelativeOutput, HolonomicPathFollowerConfig config, frc2::Subsystem *driveSubsystem)
Definition: AutoBuilder.cpp:33
+
static frc2::CommandPtr getAutoCommandFromJson(const wpi::json &json)
Definition: AutoBuilder.cpp:282
+
static frc2::CommandPtr pathfindToPose(frc::Pose2d pose, PathConstraints constraints, units::meters_per_second_t goalEndVel=0_mps, units::meter_t rotationDelayDistance=0_m)
Definition: AutoBuilder.cpp:306
+
static void configureCustom(std::function< frc2::CommandPtr(std::shared_ptr< PathPlannerPath >)> pathFollowingCommandBuilder, std::function< frc::Pose2d()> poseSupplier, std::function< void(frc::Pose2d)> resetPose)
Definition: AutoBuilder.cpp:237
+
static frc2::CommandPtr buildAuto(std::string autoName)
Definition: AutoBuilder.cpp:265
+
static bool isConfigured()
Definition: AutoBuilder.h:132
+
static frc2::CommandPtr pathfindThenFollowPath(std::shared_ptr< PathPlannerPath > goalPath, PathConstraints pathfindingConstraints, units::meter_t rotationDelayDistance=0_m)
Definition: AutoBuilder.cpp:318
+
static void configureLTV(std::function< frc::Pose2d()> poseSupplier, std::function< void(frc::Pose2d)> resetPose, std::function< frc::ChassisSpeeds()> speedsSupplier, std::function< void(frc::ChassisSpeeds)> output, const wpi::array< double, 3 > &Qelms, const wpi::array< double, 2 > &Relms, units::second_t dt, ReplanningConfig replanningConfig, frc2::Subsystem *driveSubsystem)
Definition: AutoBuilder.cpp:156
+
Definition: HolonomicPathFollowerConfig.h:10
+
Definition: PathConstraints.h:10
+
Definition: ReplanningConfig.h:6
+