Package com.thunder.lib.auto
Class ThunderAutoTrajectory
java.lang.Object
com.thunder.lib.auto.ThunderAutoTrajectory
- All Implemented Interfaces:
ThunderTrajectory
Represents a ThunderAuto trajectory.
-
Method Summary
Modifier and TypeMethodDescriptiongetActionsAtTime(double timeSeconds) Get actions to perform at the specified time during the trajectory.Get times at which actions are to be performed during the trajectory.doubleReturns the duration of the trajectory.Gets the end action to perform after finishing the trajectory.Returns the final state of the robot.Returns the initial state of the robot.Gets the start action to perform before starting the trajectory.getStopAction(double stopTimeSeconds) Gets the action to perform when the robot is stopped.Get times at which the robot comes to a complete stop during the trajectory.booleanisValid()Checks if the trajectory is valid.sample(double timeSeconds) Samples the trajectory at a specified time.
-
Method Details
-
isValid
public boolean isValid()Description copied from interface:ThunderTrajectoryChecks if the trajectory is valid.- Specified by:
isValidin interfaceThunderTrajectory- Returns:
- True or false.
-
sample
Description copied from interface:ThunderTrajectorySamples the trajectory at a specified time.- Specified by:
samplein interfaceThunderTrajectory- Parameters:
timeSeconds- The time at which to sample the trajectory.- Returns:
- The state of the robot at the specified time.
-
getDurationSeconds
public double getDurationSeconds()Description copied from interface:ThunderTrajectoryReturns the duration of the trajectory.- Specified by:
getDurationSecondsin interfaceThunderTrajectory- Returns:
- The duration.
-
getInitialState
Description copied from interface:ThunderTrajectoryReturns the initial state of the robot.- Specified by:
getInitialStatein interfaceThunderTrajectory- Returns:
- The initial state.
-
getFinalState
Description copied from interface:ThunderTrajectoryReturns the final state of the robot.- Specified by:
getFinalStatein interfaceThunderTrajectory- Returns:
- The final state.
-
getStartAction
Gets the start action to perform before starting the trajectory.- Returns:
- Action name, or an empty optional if there is no start action to perform.
-
getEndAction
Gets the end action to perform after finishing the trajectory.- Returns:
- Action name, or an empty optional if there is no end action to perform.
-
getStopTimes
Get times at which the robot comes to a complete stop during the trajectory.- Returns:
- List of stop times in seconds
-
getStopAction
Gets the action to perform when the robot is stopped. This action must complete before the robot resumes driving. If the robot is not stopped at the specified time or there is no stop action to perform at the stop time, an empty optional will be returned- Parameters:
stopTimeSeconds- Stop time in seconds- Returns:
- Action name, or an empty optional.
-
getActionTimes
Get times at which actions are to be performed during the trajectory.- Returns:
- List of action times in seconds
-
getActionsAtTime
Get actions to perform at the specified time during the trajectory. This function simply returns the actions scheduled to start at the specified time, which is usually retrieved from getActionTimes(). Actions may continue running beyond the specified time, but this function will not return those.- Parameters:
timeSeconds- Time in seconds- Returns:
- Set of action names
-