Class AutoFactory
Here is an example of how to use this class to create an auto routine:
Example using Trigger
s
public AutoRoutine shootThenMove(AutoFactory factory) {
// Create a new auto routine to return
var routine = factory.newRoutine();
// Create a trajectory that moves the robot 2 meters
AutoTrajectory trajectory = factory.trajectory("move2meters", routine);
// Will automatically run the shoot command when the auto routine is first polled
routine.enabled().onTrue(shooter.shoot());
// Gets a trigger from the shooter to if the shooter has a note, and will run the trajectory
// command when the shooter does not have a note
routine.enabled().and(shooter.hasNote()).onFalse(trajectory.cmd());
return routine;
}
Example using CommandGroup
s
public Command shootThenMove(AutoFactory factory) {
// Create a trajectory that moves the robot 2 meters
Command trajectory = factory.trajectoryCommand("move2meters");
return shooter.shoot()
.andThen(trajectory)
.withName("ShootThenMove");
}
-
Nested Class Summary
Modifier and TypeClassDescriptionstatic class
A class used to bind commands to events in all trajectories created by this factory. -
Constructor Summary
ConstructorDescriptionAutoFactory
(Supplier<Pose2d> poseSupplier, BiConsumer<Pose2d, SampleType> controller, BooleanSupplier mirrorTrajectory, Subsystem driveSubsystem, AutoFactory.AutoBindings bindings, Optional<Choreo.TrajectoryLogger<SampleType>> trajectoryLogger) Its recommended to use theChoreo.createAutoFactory(java.util.function.Supplier<edu.wpi.first.math.geometry.Pose2d>, java.util.function.BiConsumer<edu.wpi.first.math.geometry.Pose2d, SampleType>, java.util.function.BooleanSupplier, edu.wpi.first.wpilibj2.command.Subsystem, choreo.auto.AutoFactory.AutoBindings)
to create a new instance of this class. -
Method Summary
Modifier and TypeMethodDescriptionvoid
Binds a command to an event in all trajectories created after this point.void
TheAutoFactory
caches trajectories with aChoreo.TrajectoryCache
to avoid reloading the same trajectory multiple times.Creates anAutoRoutine
with the name of the command.newRoutine
(String name) Creates a newAutoRoutine
.<SampleType extends TrajectorySample<SampleType>>
AutoTrajectorytrajectory
(Trajectory<SampleType> trajectory, AutoRoutine routine) Creates a new auto trajectory to be used in an auto routine.trajectory
(String trajectoryName, int splitIndex, AutoRoutine routine) Creates a new auto trajectory to be used in an auto routine.trajectory
(String trajectoryName, AutoRoutine routine) Creates a new auto trajectory to be used in an auto routine.<SampleType extends TrajectorySample<SampleType>>
CommandtrajectoryCommand
(Trajectory<SampleType> trajectory) Creates a new auto trajectory command to be used in an auto routine.trajectoryCommand
(String trajectoryName) Creates a new auto trajectory command to be used in an auto routine.trajectoryCommand
(String trajectoryName, int splitIndex) Creates a new auto trajectory command to be used in an auto routine.AnAutoRoutine
that cannot have any side-effects, it stores no state and does nothing when polled.
-
Constructor Details
-
AutoFactory
public AutoFactory(Supplier<Pose2d> poseSupplier, BiConsumer<Pose2d, SampleType> controller, BooleanSupplier mirrorTrajectory, Subsystem driveSubsystem, AutoFactory.AutoBindings bindings, Optional<Choreo.TrajectoryLogger<SampleType>> trajectoryLogger) Its recommended to use theChoreo.createAutoFactory(java.util.function.Supplier<edu.wpi.first.math.geometry.Pose2d>, java.util.function.BiConsumer<edu.wpi.first.math.geometry.Pose2d, SampleType>, java.util.function.BooleanSupplier, edu.wpi.first.wpilibj2.command.Subsystem, choreo.auto.AutoFactory.AutoBindings)
to create a new instance of this class.- Type Parameters:
SampleType
-Choreo.createAutoFactory(java.util.function.Supplier<edu.wpi.first.math.geometry.Pose2d>, java.util.function.BiConsumer<edu.wpi.first.math.geometry.Pose2d, SampleType>, java.util.function.BooleanSupplier, edu.wpi.first.wpilibj2.command.Subsystem, choreo.auto.AutoFactory.AutoBindings)
- Parameters:
poseSupplier
-Choreo.createAutoFactory(java.util.function.Supplier<edu.wpi.first.math.geometry.Pose2d>, java.util.function.BiConsumer<edu.wpi.first.math.geometry.Pose2d, SampleType>, java.util.function.BooleanSupplier, edu.wpi.first.wpilibj2.command.Subsystem, choreo.auto.AutoFactory.AutoBindings)
controller
-Choreo.createAutoFactory(java.util.function.Supplier<edu.wpi.first.math.geometry.Pose2d>, java.util.function.BiConsumer<edu.wpi.first.math.geometry.Pose2d, SampleType>, java.util.function.BooleanSupplier, edu.wpi.first.wpilibj2.command.Subsystem, choreo.auto.AutoFactory.AutoBindings)
mirrorTrajectory
-Choreo.createAutoFactory(java.util.function.Supplier<edu.wpi.first.math.geometry.Pose2d>, java.util.function.BiConsumer<edu.wpi.first.math.geometry.Pose2d, SampleType>, java.util.function.BooleanSupplier, edu.wpi.first.wpilibj2.command.Subsystem, choreo.auto.AutoFactory.AutoBindings)
driveSubsystem
-Choreo.createAutoFactory(java.util.function.Supplier<edu.wpi.first.math.geometry.Pose2d>, java.util.function.BiConsumer<edu.wpi.first.math.geometry.Pose2d, SampleType>, java.util.function.BooleanSupplier, edu.wpi.first.wpilibj2.command.Subsystem, choreo.auto.AutoFactory.AutoBindings)
bindings
-Choreo.createAutoFactory(java.util.function.Supplier<edu.wpi.first.math.geometry.Pose2d>, java.util.function.BiConsumer<edu.wpi.first.math.geometry.Pose2d, SampleType>, java.util.function.BooleanSupplier, edu.wpi.first.wpilibj2.command.Subsystem, choreo.auto.AutoFactory.AutoBindings)
trajectoryLogger
-Choreo.createAutoFactory(java.util.function.Supplier<edu.wpi.first.math.geometry.Pose2d>, java.util.function.BiConsumer<edu.wpi.first.math.geometry.Pose2d, SampleType>, java.util.function.BooleanSupplier, edu.wpi.first.wpilibj2.command.Subsystem, choreo.auto.AutoFactory.AutoBindings)
-
-
Method Details
-
newRoutine
Creates a newAutoRoutine
.- Parameters:
name
- The name of theAutoRoutine
.- Returns:
- A new
AutoRoutine
. - See Also:
-
voidRoutine
AnAutoRoutine
that cannot have any side-effects, it stores no state and does nothing when polled.- Returns:
- A void
AutoRoutine
. - See Also:
-
trajectory
Creates a new auto trajectory to be used in an auto routine.- Parameters:
trajectoryName
- The name of the trajectory to use.routine
- TheAutoRoutine
to register this trajectory under.- Returns:
- A new auto trajectory.
-
trajectory
Creates a new auto trajectory to be used in an auto routine.- Parameters:
trajectoryName
- The name of the trajectory to use.splitIndex
- The index of the split trajectory to use.routine
- TheAutoRoutine
to register this trajectory under.- Returns:
- A new auto trajectory.
-
trajectory
public <SampleType extends TrajectorySample<SampleType>> AutoTrajectory trajectory(Trajectory<SampleType> trajectory, AutoRoutine routine) Creates a new auto trajectory to be used in an auto routine.- Type Parameters:
SampleType
- The type of the trajectory samples.- Parameters:
trajectory
- The trajectory to use.routine
- TheAutoRoutine
to register this trajectory under.- Returns:
- A new auto trajectory.
-
trajectoryCommand
Creates a new auto trajectory command to be used in an auto routine.Important
trajectoryCommand(java.lang.String)
andtrajectory(java.lang.String, choreo.auto.AutoRoutine)
methods should not be mixed in the same auto routine.trajectoryCommand(java.lang.String)
is used as an escape hatch for teams that don't need the benefits of thetrajectory(java.lang.String, choreo.auto.AutoRoutine)
method and itsTrigger
API.trajectoryCommand(java.lang.String)
does not invoke bindings added via callingbind(java.lang.String, edu.wpi.first.wpilibj2.command.Command)
orAutoFactory.AutoBindings
passed into the factory constructor.- Parameters:
trajectoryName
- The name of the trajectory to use.- Returns:
- A new auto trajectory.
-
trajectoryCommand
Creates a new auto trajectory command to be used in an auto routine.Important
trajectoryCommand(java.lang.String)
andtrajectory(java.lang.String, choreo.auto.AutoRoutine)
methods should not be mixed in the same auto routine.trajectoryCommand(java.lang.String)
is used as an escape hatch for teams that don't need the benefits of thetrajectory(java.lang.String, choreo.auto.AutoRoutine)
method and itsTrigger
API.trajectoryCommand(java.lang.String)
does not invoke bindings added via callingbind(java.lang.String, edu.wpi.first.wpilibj2.command.Command)
orAutoFactory.AutoBindings
passed into the factory constructor.- Parameters:
trajectoryName
- The name of the trajectory to use.splitIndex
- The index of the split trajectory to use.- Returns:
- A new auto trajectory.
-
trajectoryCommand
public <SampleType extends TrajectorySample<SampleType>> Command trajectoryCommand(Trajectory<SampleType> trajectory) Creates a new auto trajectory command to be used in an auto routine.Important
trajectoryCommand(java.lang.String)
andtrajectory(java.lang.String, choreo.auto.AutoRoutine)
methods should not be mixed in the same auto routine.trajectoryCommand(java.lang.String)
is used as an escape hatch for teams that don't need the benefits of thetrajectory(java.lang.String, choreo.auto.AutoRoutine)
method and itsTrigger
API.trajectoryCommand(java.lang.String)
does not invoke bindings added via callingbind(java.lang.String, edu.wpi.first.wpilibj2.command.Command)
orAutoFactory.AutoBindings
passed into the factory constructor.- Type Parameters:
SampleType
- The type of the trajectory samples.- Parameters:
trajectory
- The trajectory to use.- Returns:
- A new auto trajectory.
-
commandAsAutoRoutine
Creates anAutoRoutine
with the name of the command. The command is the bound to the routine's enabled trigger. This is useful for adding aCommand
composition based auto to theAutoChooser
.- Parameters:
cmd
- The command to bind to the routine.- Returns:
- A new auto routine.
-
bind
Binds a command to an event in all trajectories created after this point.- Parameters:
name
- The name of the trajectory to bind the command to.cmd
- The command to bind to the trajectory.
-
clearCache
TheAutoFactory
caches trajectories with aChoreo.TrajectoryCache
to avoid reloading the same trajectory multiple times. This can have the side effect of keeping a single copy of every trajectory ever loaded in memory aslong as the factory is loaded. This method clears the cache of all trajectories.Usage Note:
Never clearing the cache is unlikely to have an impact on the robots performance on a rio 2
-