Class AutoFactory
AutoRoutine
s and AutoTrajectory
s.- See Also:
-
Constructor Summary
ConstructorsConstructorDescriptionAutoFactory
(Supplier<Pose2d> poseSupplier, Consumer<Pose2d> resetOdometry, Consumer<SampleType> controller, boolean useAllianceFlipping, Subsystem driveSubsystem, Choreo.TrajectoryLogger<SampleType> trajectoryLogger) Create a factory that can be used to createAutoRoutine
andAutoTrajectory
.AutoFactory
(Supplier<Pose2d> poseSupplier, Consumer<Pose2d> resetOdometry, Consumer<ST> controller, boolean useAllianceFlipping, Subsystem driveSubsystem) Create a factory that can be used to createAutoRoutine
andAutoTrajectory
. -
Method Summary
Modifier and TypeMethodDescriptionBinds a command to an event in all trajectories created after this point.cache()
TheAutoFactory
caches trajectories with aChoreo.TrajectoryCache
to avoid reloading the same trajectory multiple times.newRoutine
(String name) Creates a newAutoRoutine
.<ST extends TrajectorySample<ST>>
CommandresetOdometry
(Trajectory<ST> trajectory) Creates a command that resets the robot's odometry to the start of a trajectory.resetOdometry
(String trajectoryName) Creates a command that resets the robot's odometry to the start of a trajectory.resetOdometry
(String trajectoryName, int splitIndex) Creates a command that resets the robot's odometry to the start of a trajectory.<ST extends TrajectorySample<ST>>
CommandtrajectoryCmd
(Trajectory<ST> trajectory) Creates a newAutoTrajectory
command to be used in an auto routine.trajectoryCmd
(String trajectoryName) Creates a newAutoTrajectory
command to be used in an auto routine.trajectoryCmd
(String trajectoryName, int splitIndex) Creates a newAutoTrajectory
command to be used in an auto routine.
-
Constructor Details
-
AutoFactory
public AutoFactory(Supplier<Pose2d> poseSupplier, Consumer<Pose2d> resetOdometry, Consumer<SampleType> controller, boolean useAllianceFlipping, Subsystem driveSubsystem, Choreo.TrajectoryLogger<SampleType> trajectoryLogger) Create a factory that can be used to createAutoRoutine
andAutoTrajectory
.- Type Parameters:
SampleType
- The type of samples in the trajectory.- Parameters:
poseSupplier
- A function that returns the current field-relativePose2d
of the robot.resetOdometry
- A function that receives a field-relativePose2d
to reset the robot's odometry to.controller
- A function that receives the currentAutoFactory
and controls the robot.useAllianceFlipping
- If this is true, when on the red alliance, the path will be mirrored to the opposite side, while keeping the same coordinate system origin.driveSubsystem
- The driveSubsystem
to require forAutoTrajectory
Command
s.trajectoryLogger
- AChoreo.TrajectoryLogger
to logTrajectory
as they start and finish.- See Also:
-
AutoFactory
public AutoFactory(Supplier<Pose2d> poseSupplier, Consumer<Pose2d> resetOdometry, Consumer<ST> controller, boolean useAllianceFlipping, Subsystem driveSubsystem) Create a factory that can be used to createAutoRoutine
andAutoTrajectory
.- Type Parameters:
ST
-DifferentialSample
orSwerveSample
- Parameters:
poseSupplier
- A function that returns the current field-relativePose2d
of the robot.resetOdometry
- A function that receives a field-relativePose2d
to reset the robot's odometry to.controller
- A function that receives the currentAutoFactory
and controls the robot.useAllianceFlipping
- If this returns true, when on the red alliance, the path will be mirrored to the opposite side, while keeping the same coordinate system origin.driveSubsystem
- The driveSubsystem
to require forAutoTrajectory
Command
s.- See Also:
-
-
Method Details
-
newRoutine
Creates a newAutoRoutine
.- Parameters:
name
- The name of theAutoRoutine
.- Returns:
- A new
AutoRoutine
.
-
trajectoryCmd
Creates a newAutoTrajectory
command to be used in an auto routine.Important
trajectoryCmd(java.lang.String)
andtrajectory(java.lang.String, choreo.auto.AutoRoutine, boolean)
methods should not be mixed in the same auto routine.trajectoryCmd(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, boolean)
method and itsTrigger
API.trajectoryCmd(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
AutoTrajectory
.
-
trajectoryCmd
Creates a newAutoTrajectory
command to be used in an auto routine.Important
trajectoryCmd(java.lang.String)
andtrajectory(java.lang.String, choreo.auto.AutoRoutine, boolean)
methods should not be mixed in the same auto routine.trajectoryCmd(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, boolean)
method and itsTrigger
API.trajectoryCmd(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
AutoTrajectory
.
-
trajectoryCmd
Creates a newAutoTrajectory
command to be used in an auto routine.Important
trajectoryCmd(java.lang.String)
andtrajectory(java.lang.String, choreo.auto.AutoRoutine, boolean)
methods should not be mixed in the same auto routine.trajectoryCmd(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, boolean)
method and itsTrigger
API.trajectoryCmd(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:
ST
-DifferentialSample
orSwerveSample
- Parameters:
trajectory
- The trajectory to use.- Returns:
- A new
AutoTrajectory
.
-
resetOdometry
Creates a command that resets the robot's odometry to the start of a trajectory.- Parameters:
trajectoryName
- The name of the trajectory to use.- Returns:
- A command that resets the robot's odometry.
-
resetOdometry
Creates a command that resets the robot's odometry to the start of a trajectory.- Parameters:
trajectoryName
- The name of the trajectory to use.splitIndex
- The index of the split trajectory to use.- Returns:
- A command that resets the robot's odometry.
-
resetOdometry
Creates a command that resets the robot's odometry to the start of a trajectory.- Type Parameters:
ST
-DifferentialSample
orSwerveSample
- Parameters:
trajectory
- The trajectory to use.- Returns:
- A command that resets the robot's odometry.
-
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.- Returns:
- The AutoFactory the method was called from.
-
cache
TheAutoFactory
caches trajectories with aChoreo.TrajectoryCache
to avoid reloading the same trajectory multiple times.- Returns:
- The trajectory cache.
-