Class AutoTrajectory
-
Method Summary
Modifier and TypeMethodDescriptionactive()
Returns a trigger that is true while the trajectory is scheduled.Returns a trigger that is true when the robot is within toleranceMeters of the given pose.Returns a trigger that is true when the robot is within toleranceMeters and toleranceRadians of the given event's pose.atTime
(double timeSinceStart) Returns a trigger that will go true for 1 cycle when the desired time has elapsedReturns a trigger that is true when the event with the given name has been reached based on time.atTimeBeforeEnd
(double timeBeforeEnd) Returns a trigger that will go true for 1 cycle when the desired before the end of the trajectory time.atTranslation
(Translation2d translation, double toleranceMeters) Returns a trigger that is true when the robot is within toleranceMeters of the given translation.atTranslation
(String eventName, double toleranceMeters) Returns a trigger that is true when the robot is within toleranceMeters and toleranceRadians of the given event's translation.void
chain
(AutoTrajectory otherTrajectory) A shorthand for `.done().onTrue(otherTrajectory.cmd())`cmd()
Creates a command that allocates the drive subsystem and follows the trajectory using the factories control functionPose2d[]
collectEventPoses
(String eventName) Returns an array of all the poses of the events with the given name.double[]
collectEventTimes
(String eventName) Returns an array of all the timestamps of the events with the given name.done()
Returns a trigger that rises to true when the trajectory ends and falls after one pulse.done
(int cycles) Deprecated, for removal: This API element is subject to removal in a future version.doneDelayed
(double seconds) Returns a trigger that rises to true a number of cycles after the trajectory ends and falls after one pulse.doneFor
(double seconds) Returns a trigger that stays true for a number of cycles after the trajectory ends.boolean
Will get the ending pose of the trajectory.Will get the starting pose of the trajectory.<SampleType extends TrajectorySample<SampleType>>
Trajectory<SampleType>Will get the underlyingTrajectory
object.inactive()
Returns a trigger that is true while the command is not scheduled.Returns a trigger that is true when the trajectory was the last one active and is done.Creates a command that resets the robot's odometry to the start of this trajectory.spawnCmd()
Creates a command that will schedule another command that will follow the trajectory.
-
Method Details
-
cmd
Creates a command that allocates the drive subsystem and follows the trajectory using the factories control function- Returns:
- The command that will follow the trajectory
-
spawnCmd
Creates a command that will schedule another command that will follow the trajectory.This can be useful when putting
AutoTrajectory
commands in sequences that require subsystems also required by in AutoTrajectory-bound subsystems.- Returns:
- The command that will schedule the trajectory following command.
-
resetOdometry
Creates a command that resets the robot's odometry to the start of this trajectory.- Returns:
- A command that resets the robot's odometry.
-
getRawTrajectory
Will get the underlyingTrajectory
object.WARNING: This method is not type safe and should be used with caution. The sample type of the trajectory should be known before calling this method.
- Type Parameters:
SampleType
- The type of the trajectory samples.- Returns:
- The underlying
Trajectory
object.
-
getInitialPose
Will get the starting pose of the trajectory.This position is flipped if alliance flipping is enabled and the alliance supplier returns Red.
This method returns an empty Optional if the trajectory is empty. This method returns an empty Optional if alliance flipping is enabled and the alliance supplier returns an empty Optional.
- Returns:
- The starting pose
-
getFinalPose
Will get the ending pose of the trajectory.This position is flipped if alliance flipping is enabled and the alliance supplier returns Red.
This method returns an empty Optional if the trajectory is empty. This method returns an empty Optional if alliance flipping is enabled and the alliance supplier returns an empty Optional.
- Returns:
- The starting pose
-
active
Returns a trigger that is true while the trajectory is scheduled.- Returns:
- A trigger that is true while the trajectory is scheduled.
-
inactive
Returns a trigger that is true while the command is not scheduled.The same as calling
active().negate()
.- Returns:
- A trigger that is true while the command is not scheduled.
-
doneDelayed
Returns a trigger that rises to true a number of cycles after the trajectory ends and falls after one pulse.This is different from inactive() in a few ways.
- This will never be true if the trajectory is interrupted
- This will never be true before the trajectory is run
- This will fall the next cycle after the trajectory ends
Why does the trigger need to fall?
//Lets say we had this code segment Trigger hasGamepiece = ...; Trigger noGamepiece = hasGamepiece.negate(); AutoTrajectory rushMidTraj = ...; AutoTrajectory goShootGamepiece = ...; AutoTrajectory pickupAnotherGamepiece = ...; routine.enabled().onTrue(rushMidTraj.cmd()); rushMidTraj.doneDelayed(10).and(noGamepiece).onTrue(pickupAnotherGamepiece.cmd()); rushMidTraj.doneDelayed(10).and(hasGamepiece).onTrue(goShootGamepiece.cmd()); // If done never falls when a new trajectory is scheduled // then these triggers leak into the next trajectory, causing the next note pickup // to trigger goShootGamepiece.cmd() even if we no longer care about these checks
- Parameters:
seconds
- The seconds to delay the trigger from rising to true.- Returns:
- A trigger that is true when the trajectory is finished.
-
done
Deprecated, for removal: This API element is subject to removal in a future version.UsedoneDelayed(int)
instead.Returns a trigger that rises to true a number of cycles after the trajectory ends and falls after one pulse.- Parameters:
cycles
- The number of cycles to delay the trigger from rising to true.- Returns:
- A trigger that is true when the trajectory is finished.
- See Also:
-
done
Returns a trigger that rises to true when the trajectory ends and falls after one pulse.This is different from inactive() in a few ways.
- This will never be true if the trajectory is interrupted
- This will never be true before the trajectory is run
- This will fall the next cycle after the trajectory ends
Why does the trigger need to fall?
//Lets say we had this code segment Trigger hasGamepiece = ...; Trigger noGamepiece = hasGamepiece.negate(); AutoTrajectory rushMidTraj = ...; AutoTrajectory goShootGamepiece = ...; AutoTrajectory pickupAnotherGamepiece = ...; routine.enabled().onTrue(rushMidTraj.cmd()); rushMidTraj.done().and(noGamepiece).onTrue(pickupAnotherGamepiece.cmd()); rushMidTraj.done().and(hasGamepiece).onTrue(goShootGamepiece.cmd()); // If done never falls when a new trajectory is scheduled // then these triggers leak into the next trajectory, causing the next note pickup // to trigger goShootGamepiece.cmd() even if we no longer care about these checks
- Returns:
- A trigger that is true when the trajectory is finished.
-
doneFor
Returns a trigger that stays true for a number of cycles after the trajectory ends.- Parameters:
seconds
- Seconds to stay true after the trajectory ends.- Returns:
- A trigger that stays true for a number of cycles after the trajectory ends.
-
recentlyDone
Returns a trigger that is true when the trajectory was the last one active and is done.- Returns:
- A trigger that is true when the trajectory was the last one active and is done.
-
chain
A shorthand for `.done().onTrue(otherTrajectory.cmd())`- Parameters:
otherTrajectory
- The other trajectory to run when this one is done.
-
atTime
Returns a trigger that will go true for 1 cycle when the desired time has elapsed- Parameters:
timeSinceStart
- The time since the command started in seconds.- Returns:
- A trigger that is true when timeSinceStart has elapsed.
-
atTimeBeforeEnd
Returns a trigger that will go true for 1 cycle when the desired before the end of the trajectory time.- Parameters:
timeBeforeEnd
- The time before the end of the trajectory.- Returns:
- A trigger that is true when timeBeforeEnd has elapsed.
-
atTime
Returns a trigger that is true when the event with the given name has been reached based on time.A warning will be printed to the DriverStation if the event is not found and the trigger will always be false.
- Parameters:
eventName
- The name of the event.- Returns:
- A trigger that is true when the event with the given name has been reached based on time.
- See Also:
-
atPose
Returns a trigger that is true when the robot is within toleranceMeters of the given pose.The pose is flipped if alliance flipping is enabled and the alliance supplier returns Red.
While alliance flipping is enabled and the alliance supplier returns empty, the trigger will return false.
- Parameters:
pose
- The pose to check against, unflipped.toleranceMeters
- The tolerance in meters.toleranceRadians
- The heading tolerance in radians.- Returns:
- A trigger that is true when the robot is within toleranceMeters of the given pose.
-
atPose
Returns a trigger that is true when the robot is within toleranceMeters and toleranceRadians of the given event's pose.A warning will be printed to the DriverStation if the event is not found and the trigger will always be false.
- Parameters:
eventName
- The name of the event.toleranceMeters
- The tolerance in meters.toleranceRadians
- The heading tolerance in radians.- Returns:
- A trigger that is true when the robot is within toleranceMeters of the given events pose.
- See Also:
-
atTranslation
Returns a trigger that is true when the robot is within toleranceMeters of the given translation.The translation is flipped if alliance flipping is enabled and the alliance supplier returns Red.
While alliance flipping is enabled and the alliance supplier returns empty, the trigger will return false.
- Parameters:
translation
- The translation to check against, unflipped.toleranceMeters
- The tolerance in meters.- Returns:
- A trigger that is true when the robot is within toleranceMeters of the given translation.
-
atTranslation
Returns a trigger that is true when the robot is within toleranceMeters and toleranceRadians of the given event's translation.A warning will be printed to the DriverStation if the event is not found and the trigger will always be false.
- Parameters:
eventName
- The name of the event.toleranceMeters
- The tolerance in meters.- Returns:
- A trigger that is true when the robot is within toleranceMeters of the given events translation.
- See Also:
-
collectEventTimes
Returns an array of all the timestamps of the events with the given name.- Parameters:
eventName
- The name of the event.- Returns:
- An array of all the timestamps of the events with the given name.
- See Also:
-
collectEventPoses
Returns an array of all the poses of the events with the given name.The returned poses are always unflipped. If you use them in a trigger like `atPose` or `atTranslation`, the library will automatically flip them if necessary. If you intend using them in a different context, you can use
ChoreoAllianceFlipUtil.flip(edu.wpi.first.math.geometry.Translation2d)
to flip them.- Parameters:
eventName
- The name of the event.- Returns:
- An array of all the poses of the events with the given name.
- See Also:
-
equals
-
doneDelayed(int)
instead.