diff --git a/src/main/java/frc/robot/autos/trailblazer/AutoSegment.java b/src/main/java/frc/robot/autos/trailblazer/AutoSegment.java index 3360a38..1bffc4a 100644 --- a/src/main/java/frc/robot/autos/trailblazer/AutoSegment.java +++ b/src/main/java/frc/robot/autos/trailblazer/AutoSegment.java @@ -3,17 +3,25 @@ import frc.robot.autos.trailblazer.constraints.AutoPointConstraint; import java.util.List; +/** + * A segment is a path (a continuous set of {@link AutoPoint points}) that the roobt will follow. + */ public class AutoSegment { public final List points; + + /** + * Constraints to apply to any points that don't have their own constraints specified. If a point + * specifies its own constraints, this field will be ignored. + */ public final List defaultConstraints; - public AutoSegment(List globalConstraints, List points) { - this.defaultConstraints = globalConstraints; + public AutoSegment(List defaultConstraints, List points) { + this.defaultConstraints = defaultConstraints; this.points = points; } - public AutoSegment(List globalConstraints, AutoPoint... points) { - this(globalConstraints, List.of(points)); + public AutoSegment(List defaultConstraints, AutoPoint... points) { + this(defaultConstraints, List.of(points)); } public AutoSegment(List points) {