Class Path
- java.lang.Object
-
- com.lightningrobotics.common.auto.Path
-
public class Path extends java.lang.ObjectObject class representing a path aLightningDrivetraincan follow.
-
-
Constructor Summary
Constructors Constructor Description Path(java.lang.String fname, boolean reversed)Constructor creates path objectPath(java.lang.String name, java.util.List<edu.wpi.first.math.geometry.Pose2d> waypoints)Constructor creates path objectPath(java.lang.String name, java.util.List<edu.wpi.first.math.geometry.Pose2d> waypoints, boolean reversed)Constructor creates path objectPath(java.util.List<edu.wpi.first.math.geometry.Pose2d> waypoints)Constructor creates path objectPath(java.util.List<edu.wpi.first.math.geometry.Pose2d> waypoints, boolean reversed)
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description edu.wpi.first.wpilibj2.command.CommandgetCommand(LightningDrivetrain drivetrain)Retrieves the path represented as a commanddoublegetDuration(LightningDrivetrain drivetrain)The duration of time it will take the robot to complete the pathjava.lang.StringgetName()Name of pathbooleangetReversed()Direction path should be followedTrajectorygetTrajectory(LightningDrivetrain drivetrain)Obtains an optimized trajectory the robot should follow so it hits all the waypoints
-
-
-
Constructor Detail
-
Path
public Path(java.util.List<edu.wpi.first.math.geometry.Pose2d> waypoints)
Constructor creates path object- Parameters:
waypoints- List of waypoints for the optimized path to follow
-
Path
public Path(java.util.List<edu.wpi.first.math.geometry.Pose2d> waypoints, boolean reversed)
-
Path
public Path(java.lang.String name, java.util.List<edu.wpi.first.math.geometry.Pose2d> waypoints)Constructor creates path object- Parameters:
name- The name of the pathwaypoints- List of waypoints for the optimized path to follow
-
Path
public Path(java.lang.String name, java.util.List<edu.wpi.first.math.geometry.Pose2d> waypoints, boolean reversed)Constructor creates path object- Parameters:
name- The name of the pathwaypoints- List of waypoints for the optimized path to followreversed- Direction robot should follow path
-
Path
public Path(java.lang.String fname, boolean reversed)Constructor creates path object- Parameters:
fname- The file name of the path to load (either a path file or a json file)reversed- Direction robot should follow path
-
-
Method Detail
-
getName
public java.lang.String getName()
Name of path- Returns:
- The name of the path
-
getReversed
public boolean getReversed()
Direction path should be followed- Returns:
- The direction the path should be followed
-
getTrajectory
public Trajectory getTrajectory(LightningDrivetrain drivetrain)
Obtains an optimized trajectory the robot should follow so it hits all the waypoints- Parameters:
drivetrain- Drivetrain object of the robot the path should be configured for- Returns:
- A trajectory the robot can follow
-
getDuration
public double getDuration(LightningDrivetrain drivetrain)
The duration of time it will take the robot to complete the path- Parameters:
drivetrain- Drivetrain object of the robot the path should be configured for- Returns:
- The number of seconds the robot will need to complete driving the path
-
getCommand
public edu.wpi.first.wpilibj2.command.Command getCommand(LightningDrivetrain drivetrain) throws java.lang.Exception
Retrieves the path represented as a command- Parameters:
drivetrain- Drivetrain object of the robot the path should be configured for- Returns:
- A
commandrepresenting the path that can be driven by the given drivetrain - Throws:
java.lang.Exception- if given drivetrain is unsupported
-
-