PathPlannerLib
Loading...
Searching...
No Matches
Pathfinder.h
1#pragma once
2
3#include "pathplanner/lib/path/GoalEndState.h"
4#include "pathplanner/lib/path/PathConstraints.h"
5#include "pathplanner/lib/path/PathPlannerPath.h"
6#include <vector>
7#include <utility>
8#include <frc/geometry/Translation2d.h>
9#include <memory>
10
11namespace pathplanner {
13public:
14 virtual ~Pathfinder() {
15 }
16
22 virtual bool isNewPathAvailable() = 0;
23
31 virtual std::shared_ptr<PathPlannerPath> getCurrentPath(
32 PathConstraints constraints, GoalEndState goalEndState) = 0;
33
40 virtual void setStartPosition(const frc::Translation2d &startPosition) = 0;
41
48 virtual void setGoalPosition(const frc::Translation2d &goalPosition) = 0;
49
58 virtual void setDynamicObstacles(
59 const std::vector<std::pair<frc::Translation2d, frc::Translation2d>> &obs,
60 const frc::Translation2d &currentRobotPos) = 0;
61};
62}
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 &currentRobotPos)=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