Package com.pathplanner.lib.controllers
Class PPLTVController
java.lang.Object
edu.wpi.first.math.controller.LTVUnicycleController
com.pathplanner.lib.controllers.PPLTVController
- All Implemented Interfaces:
PathFollowingController
LTV following controller
-
Constructor Summary
ConstructorDescriptionPPLTVController
(double dt) Constructs a linear time-varying unicycle controller with default maximum desired error tolerances of (0.0625 m, 0.125 m, 2 rad) and default maximum desired control effort of (1 m/s, 2 rad/s).PPLTVController
(double dt, double maxVelocity) Constructs a linear time-varying unicycle controller with default maximum desired error tolerances of (0.0625 m, 0.125 m, 2 rad) and default maximum desired control effort of (1 m/s, 2 rad/s).PPLTVController
(Vector<N3> qelems, Vector<N2> relems, double dt) Constructs a linear time-varying unicycle controller.PPLTVController
(Vector<N3> qelems, Vector<N2> relems, double dt, double maxVelocity) Constructs a linear time-varying unicycle controller. -
Method Summary
Modifier and TypeMethodDescriptioncalculateRobotRelativeSpeeds
(Pose2d currentPose, PathPlannerTrajectoryState targetState) Calculates the next output of the path following controllerboolean
Is this controller for holonomic drivetrains? Used to handle some differences in functionality in the path following command.void
reset
(Pose2d currentPose, ChassisSpeeds currentSpeeds) Resets the controller based on the current state of the robotMethods inherited from class edu.wpi.first.math.controller.LTVUnicycleController
atReference, calculate, calculate, setEnabled, setTolerance
-
Constructor Details
-
PPLTVController
public PPLTVController(double dt) Constructs a linear time-varying unicycle controller with default maximum desired error tolerances of (0.0625 m, 0.125 m, 2 rad) and default maximum desired control effort of (1 m/s, 2 rad/s).- Parameters:
dt
- Discretization timestep in seconds.
-
PPLTVController
public PPLTVController(double dt, double maxVelocity) Constructs a linear time-varying unicycle controller with default maximum desired error tolerances of (0.0625 m, 0.125 m, 2 rad) and default maximum desired control effort of (1 m/s, 2 rad/s).- Parameters:
dt
- Discretization timestep in seconds.maxVelocity
- The maximum velocity in meters per second for the controller gain lookup table. The default is 9 m/s.- Throws:
IllegalArgumentException
- if maxVelocity <= 0.
-
PPLTVController
Constructs a linear time-varying unicycle controller.See https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning for how to select the tolerances.
- Parameters:
qelems
- The maximum desired error tolerance for each state.relems
- The maximum desired control effort for each input.dt
- Discretization timestep in seconds.
-
PPLTVController
Constructs a linear time-varying unicycle controller.See https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning for how to select the tolerances.
- Parameters:
qelems
- The maximum desired error tolerance for each state.relems
- The maximum desired control effort for each input.dt
- Discretization timestep in seconds.maxVelocity
- The maximum velocity in meters per second for the controller gain lookup table. The default is 9 m/s.- Throws:
IllegalArgumentException
- if maxVelocity <= 0 m/s or >= 15 m/s.
-
-
Method Details
-
calculateRobotRelativeSpeeds
public ChassisSpeeds calculateRobotRelativeSpeeds(Pose2d currentPose, PathPlannerTrajectoryState targetState) Calculates the next output of the path following controller- Specified by:
calculateRobotRelativeSpeeds
in interfacePathFollowingController
- Parameters:
currentPose
- The current robot posetargetState
- The desired trajectory state- Returns:
- The next robot relative output of the path following controller
-
reset
Resets the controller based on the current state of the robot- Specified by:
reset
in interfacePathFollowingController
- Parameters:
currentPose
- Current robot posecurrentSpeeds
- Current robot relative chassis speeds
-
isHolonomic
public boolean isHolonomic()Is this controller for holonomic drivetrains? Used to handle some differences in functionality in the path following command.- Specified by:
isHolonomic
in interfacePathFollowingController
- Returns:
- True if this controller is for a holonomic drive train
-