3#include "pathplanner/lib/pathfinding/Pathfinder.h"
14 static inline void setPathfinder(std::unique_ptr<Pathfinder> pathfinder) {
15 Pathfinding::pathfinder = std::move(pathfinder);
27 return pathfinder->isNewPathAvailable();
39 return pathfinder->getCurrentPath(constraints, goalEndState);
49 const frc::Translation2d &startPosition) {
50 pathfinder->setStartPosition(startPosition);
60 pathfinder->setGoalPosition(goalPosition);
72 const std::vector<std::pair<frc::Translation2d, frc::Translation2d>> &obs,
73 const frc::Translation2d ¤tRobotPos) {
74 pathfinder->setDynamicObstacles(obs, currentRobotPos);
78 static std::unique_ptr<Pathfinder> pathfinder;
Definition: GoalEndState.h:9
Definition: PathConstraints.h:12
Definition: Pathfinding.h:7
static void setGoalPosition(const frc::Translation2d &goalPosition)
Definition: Pathfinding.h:59
static void setPathfinder(std::unique_ptr< Pathfinder > pathfinder)
Definition: Pathfinding.h:14
static std::shared_ptr< PathPlannerPath > getCurrentPath(PathConstraints constraints, GoalEndState goalEndState)
Definition: Pathfinding.h:37
static void setStartPosition(const frc::Translation2d &startPosition)
Definition: Pathfinding.h:48
static bool isNewPathAvailable()
Definition: Pathfinding.h:26
static void setDynamicObstacles(const std::vector< std::pair< frc::Translation2d, frc::Translation2d > > &obs, const frc::Translation2d ¤tRobotPos)
Definition: Pathfinding.h:71
static void ensureInitialized()
Definition: Pathfinding.cpp:9