Robot Core Documentation
Loading...
Searching...
No Matches
com.pathplanner.lib.commands.FollowPathLTV Class Reference
Inheritance diagram for com.pathplanner.lib.commands.FollowPathLTV:
com.pathplanner.lib.commands.FollowPathCommand edu.wpi.first.wpilibj2.command.Command edu.wpi.first.util.sendable.Sendable

Public Member Functions

 FollowPathLTV (PathPlannerPath path, Supplier< Pose2d > poseSupplier, Supplier< ChassisSpeeds > speedsSupplier, Consumer< ChassisSpeeds > output, double dt, ReplanningConfig replanningConfig, BooleanSupplier shouldFlipPath, Subsystem... requirements)
 
 FollowPathLTV (PathPlannerPath path, Supplier< Pose2d > poseSupplier, Supplier< ChassisSpeeds > speedsSupplier, Consumer< ChassisSpeeds > output, Vector< N3 > qelems, Vector< N2 > relems, double dt, ReplanningConfig replanningConfig, BooleanSupplier shouldFlipPath, Subsystem... requirements)
 
- Public Member Functions inherited from com.pathplanner.lib.commands.FollowPathCommand
 FollowPathCommand (PathPlannerPath path, Supplier< Pose2d > poseSupplier, Supplier< ChassisSpeeds > speedsSupplier, Consumer< ChassisSpeeds > outputRobotRelative, PathFollowingController controller, ReplanningConfig replanningConfig, BooleanSupplier shouldFlipPath, Subsystem... requirements)
 
void initialize ()
 
void execute ()
 
boolean isFinished ()
 
void end (boolean interrupted)
 
- Public Member Functions inherited from edu.wpi.first.wpilibj2.command.Command
Set< SubsystemgetRequirements ()
 
final void addRequirements (Subsystem... requirements)
 
String getName ()
 
void setName (String name)
 
String getSubsystem ()
 
void setSubsystem (String subsystem)
 
ParallelRaceGroup withTimeout (double seconds)
 
ParallelRaceGroup until (BooleanSupplier condition)
 
ParallelRaceGroup onlyWhile (BooleanSupplier condition)
 
SequentialCommandGroup beforeStarting (Runnable toRun, Subsystem... requirements)
 
SequentialCommandGroup beforeStarting (Command before)
 
SequentialCommandGroup andThen (Runnable toRun, Subsystem... requirements)
 
SequentialCommandGroup andThen (Command... next)
 
ParallelDeadlineGroup deadlineWith (Command... parallel)
 
ParallelCommandGroup alongWith (Command... parallel)
 
ParallelRaceGroup raceWith (Command... parallel)
 
RepeatCommand repeatedly ()
 
ProxyCommand asProxy ()
 
ConditionalCommand unless (BooleanSupplier condition)
 
ConditionalCommand onlyIf (BooleanSupplier condition)
 
WrapperCommand ignoringDisable (boolean doesRunWhenDisabled)
 
WrapperCommand withInterruptBehavior (InterruptionBehavior interruptBehavior)
 
WrapperCommand finallyDo (BooleanConsumer end)
 
WrapperCommand finallyDo (Runnable end)
 
WrapperCommand handleInterrupt (Runnable handler)
 
void schedule ()
 
void cancel ()
 
boolean isScheduled ()
 
boolean hasRequirement (Subsystem requirement)
 
InterruptionBehavior getInterruptionBehavior ()
 
boolean runsWhenDisabled ()
 
WrapperCommand withName (String name)
 
void initSendable (SendableBuilder builder)
 
- Public Member Functions inherited from edu.wpi.first.util.sendable.Sendable

Additional Inherited Members

- Static Public Member Functions inherited from com.pathplanner.lib.commands.FollowPathCommand
- Protected Member Functions inherited from edu.wpi.first.wpilibj2.command.Command
 Command ()
 
- Protected Attributes inherited from edu.wpi.first.wpilibj2.command.Command
Set< Subsystemm_requirements = new HashSet<>()
 

Detailed Description

Follow a path using a PPLTVController

Constructor & Destructor Documentation

◆ FollowPathLTV() [1/2]

com.pathplanner.lib.commands.FollowPathLTV.FollowPathLTV ( PathPlannerPath path,
Supplier< Pose2d > poseSupplier,
Supplier< ChassisSpeeds > speedsSupplier,
Consumer< ChassisSpeeds > output,
double dt,
ReplanningConfig replanningConfig,
BooleanSupplier shouldFlipPath,
Subsystem... requirements )

Create a path following command that will use an LTV unicycle controller for differential drive trains

Parameters
pathThe path to follow
poseSupplierFunction that supplies the current field-relative pose of the robot
speedsSupplierFunction that supplies the current robot-relative chassis speeds
outputFunction that will apply the robot-relative output speeds of this command
dtThe amount of time between each robot control loop, default is 0.02s
replanningConfigPath replanning configuration
shouldFlipPathShould the path be flipped to the other side of the field? This will maintain a global blue alliance origin.
requirementsSubsystems required by this command, usually just the drive subsystem

◆ FollowPathLTV() [2/2]

com.pathplanner.lib.commands.FollowPathLTV.FollowPathLTV ( PathPlannerPath path,
Supplier< Pose2d > poseSupplier,
Supplier< ChassisSpeeds > speedsSupplier,
Consumer< ChassisSpeeds > output,
Vector< N3 > qelems,
Vector< N2 > relems,
double dt,
ReplanningConfig replanningConfig,
BooleanSupplier shouldFlipPath,
Subsystem... requirements )

Create a path following command that will use an LTV unicycle controller for differential drive trains

Parameters
pathThe path to follow
poseSupplierFunction that supplies the current field-relative pose of the robot
speedsSupplierFunction that supplies the current robot-relative chassis speeds
outputFunction that will apply the robot-relative output speeds of this command
qelemsThe maximum desired error tolerance for each state.
relemsThe maximum desired control effort for each input.
dtThe amount of time between each robot control loop, default is 0.02s
replanningConfigPath replanning configuration
shouldFlipPathShould the path be flipped to the other side of the field? This will maintain a global blue alliance origin.
requirementsSubsystems required by this command, usually just the drive subsystem

The documentation for this class was generated from the following file: