Package xbot.common.subsystems.drive
Class PurePursuitCommand
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
xbot.common.command.BaseCommand
xbot.common.subsystems.drive.PurePursuitCommand
- All Implemented Interfaces:
Sendable
,IPropertySupport
- Direct Known Subclasses:
ConfigurablePurePursuitCommand
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic enum
class
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.Command
Command.InterruptionBehavior
-
Field Summary
FieldsModifier and TypeFieldDescriptionprotected PurePursuitCommand.RabbitChaseInfo
protected final BaseDriveSubsystem
protected HeadingModule
protected final DoubleProperty
protected int
protected final BasePoseSubsystem
protected PIDManager
protected final DoubleProperty
Fields inherited from class xbot.common.command.BaseCommand
aKitLog, log, monitor, runningAlert
-
Constructor Summary
ConstructorsConstructorDescriptionPurePursuitCommand
(HeadingModule.HeadingModuleFactory headingModuleFactory, BasePoseSubsystem pose, BaseDriveSubsystem drive, PropertyFactory propMan) An implementation of Pure Pursuit for FRC. -
Method Summary
Modifier and TypeMethodDescriptionvoid
end
(boolean interrupted) This is the core method that looks at the point list, figures out which point to be heading towards, and doing the math on how to get there.evaluateCurrentPoint
(FieldPose robotPose) void
execute()
double
protected abstract List<RabbitPoint>
If you want to see where this command is heading in the future (for visualization purposes, perhaps) you can get that information here.protected abstract PurePursuitCommand.PointLoadingMode
void
boolean
void
setDotProductDrivingEnabled
(boolean enabled) void
setPIDs
(HeadingModule headingModule, PIDManager positionalPid) By default, the PurePursuitCommand uses the HeadingModule and PositionalPid from the DriveSubsystem.void
Methods inherited from class xbot.common.command.BaseCommand
getPrefix, includeOnSmartDashboard, includeOnSmartDashboard, requires, runsWhenDisabled, setRunsWhenDisabled
Methods inherited from class edu.wpi.first.wpilibj2.command.Command
addRequirements, addRequirements, alongWith, andThen, andThen, asProxy, beforeStarting, beforeStarting, cancel, deadlineFor, deadlineWith, finallyDo, finallyDo, getInterruptionBehavior, getName, getRequirements, getSubsystem, handleInterrupt, hasRequirement, ignoringDisable, initSendable, isScheduled, onlyIf, onlyWhile, raceWith, repeatedly, schedule, setName, setSubsystem, unless, until, withDeadline, withInterruptBehavior, withName, withTimeout, withTimeout
-
Field Details
-
poseSystem
-
drive
-
rabbitLookAhead
-
perpindicularRatioProp
-
headingModule
-
positionalPid
-
pointIndex
protected int pointIndex -
chaseData
-
-
Constructor Details
-
PurePursuitCommand
public PurePursuitCommand(HeadingModule.HeadingModuleFactory headingModuleFactory, BasePoseSubsystem pose, BaseDriveSubsystem drive, PropertyFactory propMan) An implementation of Pure Pursuit for FRC. We got the basic idea from here: http://www8.cs.umu.se/kurser/TDBD17/VT06/utdelat/Assignment%20Papers/Path%20Tracking%20for%20a%20Miniature%20Robot.pdf Fundamentally, you can add field points to this command (x,y, and rotation) and the robot will attempt to reach all those points with a smooth path. This works for any drive base, but presumably, holonomic robots can solve this problem more effectively. You will see references to rabbits, or "chasing the rabbit". This is alluding to how greyhoud races use mechanical rabbits, which is designed to always stay ahead of them, regardless of their speed. This is similiar to how, as the robot uses pure pursuit, it is always chasing a point it can never reach.- Parameters:
headingModuleFactory
- HeadingModuleFactorypose
- BasePoseSubsystemdrive
- BaseDriveSubsystempropMan
- PropertyManager
-
-
Method Details
-
setPIDs
By default, the PurePursuitCommand uses the HeadingModule and PositionalPid from the DriveSubsystem. However, if you want to change the PIDs used on the fly, you can here.- Parameters:
headingModule
- Used for rotationpositionalPid
- Used for translation
-
setPIDsToDefault
public void setPIDsToDefault() -
setDotProductDrivingEnabled
public void setDotProductDrivingEnabled(boolean enabled) -
getOriginalPoints
-
getPursuitMode
-
getPlannedPointsToVisit
If you want to see where this command is heading in the future (for visualization purposes, perhaps) you can get that information here.- Returns:
- List of points to visit
-
initialize
public void initialize()- Overrides:
initialize
in classBaseCommand
-
execute
public void execute() -
evaluateCurrentPoint
-
evaluateCurrentPoint
This is the core method that looks at the point list, figures out which point to be heading towards, and doing the math on how to get there.- Returns:
- Information about what the robot would like to do in order to reach its points.
-
end
public void end(boolean interrupted) - Overrides:
end
in classBaseCommand
-
isFinished
public boolean isFinished()- Overrides:
isFinished
in classCommand
-
getMotionBudget
public double getMotionBudget()
-