3#include "pathplanner/lib/path/GoalEndState.h"
4#include "pathplanner/lib/path/PathConstraints.h"
5#include "pathplanner/lib/path/PathPlannerPath.h"
8#include <frc/geometry/Translation2d.h>
11namespace pathplanner {
59 const std::vector<std::pair<frc::Translation2d, frc::Translation2d>> &obs,
60 const frc::Translation2d ¤tRobotPos) = 0;
Definition: GoalEndState.h:9
Definition: PathConstraints.h:12
Definition: Pathfinder.h:12
virtual void setDynamicObstacles(const std::vector< std::pair< frc::Translation2d, frc::Translation2d > > &obs, const frc::Translation2d ¤tRobotPos)=0
virtual std::shared_ptr< PathPlannerPath > getCurrentPath(PathConstraints constraints, GoalEndState goalEndState)=0
virtual void setStartPosition(const frc::Translation2d &startPosition)=0
virtual bool isNewPathAvailable()=0
virtual void setGoalPosition(const frc::Translation2d &goalPosition)=0