PathPlannerLib
Loading...
Searching...
No Matches
PathFollowingController.h
1#pragma once
2
3#include <frc/kinematics/ChassisSpeeds.h>
4#include <frc/geometry/Pose2d.h>
5#include <units/length.h>
6#include "pathplanner/lib/trajectory/PathPlannerTrajectory.h"
7
8namespace pathplanner {
10public:
11 virtual ~PathFollowingController() {
12 }
13
21 virtual frc::ChassisSpeeds calculateRobotRelativeSpeeds(
22 const frc::Pose2d &currentPose,
23 const PathPlannerTrajectoryState &targetState) = 0;
24
31 virtual void reset(const frc::Pose2d &currentPose,
32 const frc::ChassisSpeeds &currentSpeeds) = 0;
33
39 virtual units::meter_t getPositionalError() = 0;
40
47 virtual bool isHolonomic() = 0;
48};
49}
Definition: PathFollowingController.h:9
virtual frc::ChassisSpeeds calculateRobotRelativeSpeeds(const frc::Pose2d &currentPose, const PathPlannerTrajectoryState &targetState)=0
virtual void reset(const frc::Pose2d &currentPose, const frc::ChassisSpeeds &currentSpeeds)=0
virtual units::meter_t getPositionalError()=0
Definition: PathPlannerTrajectoryState.h:17