Skip to content

Commit

Permalink
English linting
Browse files Browse the repository at this point in the history
  • Loading branch information
bubner committed Dec 3, 2024
1 parent 5630bff commit aa1bcde
Show file tree
Hide file tree
Showing 57 changed files with 197 additions and 205 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -236,7 +236,7 @@ object StartingConfiguration {
private val flags = mutableSetOf<Any>()

/**
* Translate backward from the center of the field tile to your robot center as defined by your translate step.
* Translate backward from the center of the field tile to your robot center as defined by your translation step.
* This is to align your robot to touching the field wall.
*/
fun backward(translationBack: Measure<Distance>): PrebuiltPosition {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -126,12 +126,12 @@ class TaskBuilder(
apply { afterTime(dt, unit, InstantAction(f)) }

/**
* Sets the tangent of thebuilder = builder.
* Sets the tangent of the builder to respect on the next trajectories.
*/
fun setTangent(r: Rotation2d) = apply { builder = builder.setTangent(r) }

/**
* Sets the tangent of thebuilder = builder.
* Sets the tangent of the builder to respect on the next trajectories.
*/
@JvmOverloads
fun setTangent(r: Double, unit: Angle = Radians) =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
* @since 1.0.0-pre
*/
// Technically, angles are unitless dimensions
// eg Mass * Distance * Velocity<Angle> is equivalent to (Mass * Distance) / Time - otherwise known
// e.g. Mass * Distance * Velocity<Angle> is equivalent to (Mass * Distance) / Time - otherwise known
// as Power - in other words, Velocity<Angle> is /actually/ Frequency
public class Angle extends Unit<Angle> {
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ interface Measure<U : Unit<U>> : Comparable<Measure<U>> {
fun unit(): U

/**
* Converts this measure to a measure with a different unit of the same type, eg minutes to
* Converts this measure to a measure with a different unit of the same type, e.g. minutes to
* seconds. Converting to the same unit is equivalent to calling [magnitude].
*
* For Kotlin users, calling this method can be done with the notation \`in\`
Expand All @@ -61,7 +61,7 @@ interface Measure<U : Unit<U>> : Comparable<Measure<U>> {
}

/**
* Converts this measure to a measure with a different unit of the same type, eg minutes to
* Converts this measure to a measure with a different unit of the same type, e.g. minutes to
* seconds. Converting to the same unit is equivalent to calling [magnitude].
*
* ```
Expand Down Expand Up @@ -111,7 +111,7 @@ interface Measure<U : Unit<U>> : Comparable<Measure<U>> {
val numerator = (unit() as Per<*, *>).numerator()
return numerator.ofBaseUnits(baseUnitMagnitude() * other.baseUnitMagnitude())
} else if (unit() is Velocity<*> && other.unit().baseUnit == Units.Seconds) {
// Multiplying a velocity by a time, return the scalar unit (eg Distance)
// Multiplying a velocity by a time, return the scalar unit (e.g. Distance)
val numerator = (unit() as Velocity<*>).unit
return numerator.ofBaseUnits(baseUnitMagnitude() * other.baseUnitMagnitude())
} else if (other.unit() is Per<*, *>
Expand All @@ -129,7 +129,7 @@ interface Measure<U : Unit<U>> : Comparable<Measure<U>> {
.baseUnit
== (other.unit() as Per<*, *>).denominator().baseUnit)
) {
// multiplying eg meters per second * milliseconds per foot
// multiplying e.g. meters per second * milliseconds per foot
// return a scalar
return Units.Value.of(baseUnitMagnitude() * other.baseUnitMagnitude())
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,16 +7,13 @@ import java.util.Objects

/**
* A specialization of [Measure] that allows for mutability. This is intended to be used for
* memory use reasons (such as on the memory-restricted roboRIO 1 or 2 or SBC coprocessors) and
* should NOT be exposed in the public API for a class that uses it.
*
* memory use reasons and should NOT be exposed in the public API for a class that uses it.
*
* The advantage of using this class is to reuse one instance of a measurement object, as opposed
* to instantiating a new immutable instance every time an operation is performed. This will reduce
* memory pressure, but comes at the cost of increased code complexity and sensitivity to race
* conditions if misused.
*
*
* Any unsafe methods are prefixed with `mut_*`, such as [mut_plus] or
* [mut_replace]. These methods will change the internal state of the measurement
* object, and as such can be dangerous to use. They are primarily intended for use to track
Expand Down Expand Up @@ -115,7 +112,7 @@ class MutableMeasure<U : Unit<U>> private constructor(
baseUnitMagnitudeVal += other.baseUnitMagnitude()

// can't naively use magnitude += other.in(unit) because the units may not
// be scalar multiples (eg adding 0C to 100K should result in 373.15K, not 100K)
// be scalar multiples (e.g. adding 0C to 100K should result in 373.15K, not 100K)
magnitudeVal = unitVal.fromBaseUnits(baseUnitMagnitudeVal)
return this
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -281,7 +281,7 @@ private Units() {
public static final Dimensionless Value = BaseUnits.Value;

/**
* A dimensionless unit equal to to 1/100th of a {@link #Value}. A measurement of {@code
* A dimensionless unit equal to 1/100th of a {@link #Value}. A measurement of {@code
* Percent.of(42)} would be equivalent to {@code Value.of(0.42)}.
*/
public static final Dimensionless Percent = derive(Value).splitInto(100).named("Percent").symbol("%").make();
Expand Down Expand Up @@ -429,7 +429,7 @@ private Units() {
public static final Per<Voltage, Velocity<Velocity<Angle>>> VoltsPerRadianPerSecondSquared = Volts.per(RadiansPerSecond.per(Second));

/**
* Creates a unit equal to a thousandth of the base unit, eg Milliseconds = Milli(Units.Seconds).
* Creates a unit equal to a thousandth of the base unit, e.g. Milliseconds = Milli(Units.Seconds).
*
* @param <U> the type of the unit
* @param baseUnit the unit being derived from. This does not have to be the base unit of measure
Expand All @@ -442,7 +442,7 @@ public static <U extends Unit<U>> U Milli(Unit<U> baseUnit, String name, String
}

/**
* Creates a unit equal to a thousandth of the base unit, eg Milliseconds = Milli(Units.Seconds).
* Creates a unit equal to a thousandth of the base unit, e.g. Milliseconds = Milli(Units.Seconds).
*
* @param <U> the type of the unit
* @param baseUnit the unit being derived from. This does not have to be the base unit of measure
Expand All @@ -467,7 +467,7 @@ public static <U extends Unit<U>> U Micro(Unit<U> baseUnit, String name, String
}

/**
* Creates a unit equal to a millionth of the base unit, eg Microseconds = Micro(Units.Seconds).
* Creates a unit equal to a millionth of the base unit, e.g. Microseconds = Micro(Units.Seconds).
*
* @param <U> the type of the unit
* @param baseUnit the unit being derived from. This does not have to be the base unit of measure
Expand All @@ -478,7 +478,7 @@ public static <U extends Unit<U>> U Micro(Unit<U> baseUnit) {
}

/**
* Creates a unit equal to a thousand of the base unit, eg Kilograms = Kilo(Units.Grams).
* Creates a unit equal to a thousand of the base unit, e.g. Kilograms = Kilo(Units.Grams).
*
* @param <U> the type of the unit
* @param baseUnit the unit being derived from. This does not have to be the base unit of measure
Expand All @@ -491,7 +491,7 @@ public static <U extends Unit<U>> U Kilo(Unit<U> baseUnit, String name, String s
}

/**
* Creates a unit equal to a thousand of the base unit, eg Kilograms = Kilo(Units.Grams).
* Creates a unit equal to a thousand of the base unit, e.g. Kilograms = Kilo(Units.Grams).
*
* @param <U> the type of the unit
* @param baseUnit the unit being derived from. This does not have to be the base unit of measure
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ public static <D extends Unit<D>> Velocity<D> combine(Unit<D> numerator, Time pe
}

/**
* Gets the major unit being measured (eg Meters for Meters per Second).
* Gets the major unit being measured (e.g. Meters for Meters per Second).
*
* @return the major unit
*/
Expand All @@ -152,7 +152,7 @@ public D getUnit() {
}

/**
* Gets the period unit of the velocity, eg Seconds or Milliseconds.
* Gets the period unit of the velocity, e.g. Seconds or Milliseconds.
*
* @return the period unit
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ public LongStream stream() {
}

/**
* Creates a new array that contains all of the values in the set.
* Creates a new array that contains all the values in the set.
*
* @return an array containing all the values in the set
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@
*/
public abstract class AutonomousBunyipsOpMode extends BunyipsOpMode {
/**
* Used for tasks that have no timeout to generate a "estimate to OpMode completion" metric.
* Used for tasks that have no timeout to generate an "estimate to OpMode completion" metric.
* Purely visual, and does not affect the actual task (hence why this field is not exposed to FtcDashboard).
*/
public static double INFINITE_TASK_ASSUMED_DURATION_SECONDS = 5.0;
private final ArrayList<Reference<?>> opModes = new ArrayList<>();
private final ConcurrentLinkedDeque<Task> tasks = new ConcurrentLinkedDeque<>();
// Pre and post queues cannot have their tasks removed, so we can rely on their .size() methods
// Pre- and post-queues cannot have their tasks removed, so we can rely on their .size() methods
private final ConcurrentLinkedDeque<Task> postQueue = new ConcurrentLinkedDeque<>();
private final ConcurrentLinkedDeque<Task> preQueue = new ConcurrentLinkedDeque<>();
@NonNull
Expand Down Expand Up @@ -142,7 +142,7 @@ protected void onStart() {
if (isStopRequested())
return;
if (userSelection != null) {
// UserSelection will internally check opMode.isInInit() to see if it should terminate itself
// UserSelection will internally check opMode.isInInit() to see if it should terminate itself,
// but we should wait here until it has actually terminated
Threads.waitFor(userSelection, true);
}
Expand Down Expand Up @@ -217,7 +217,7 @@ public final void disableHardwareStopOnFinish() {
* the automatic collection of {@link BunyipsSubsystem}s, and allows you to determine which subsystems will be managed for
* this OpMode.
* <p>
* For most cases, using this method is not required and all you need to do is construct your subsystems and they
* For most cases, using this method is not required and all you need to do is construct your subsystems, and they
* will be managed automatically. This method is for advanced cases where you don't want this behaviour to happen.
*
* @param subsystems the restrictive list of subsystems to be managed and updated by ABOM
Expand Down Expand Up @@ -368,7 +368,7 @@ public final <T extends Task> T deferAtIndex(int index, @NonNull Supplier<T> new
}

/**
* Insert an implicit RunTask at a specific index in the queue.
* Insert an implicit {@link Lambda} at a specific index in the queue.
*
* @param index the index to insert the task at, starting from 0
* @param runnable the code to add to the run queue to run once
Expand All @@ -380,7 +380,7 @@ public final Lambda addAtIndex(int index, @NonNull Runnable runnable) {
}

/**
* Insert an implicit RunTask at a specific index in the queue.
* Insert an implicit {@link Lambda} at a specific index in the queue.
*
* @param index the index to insert the task at, starting from 0
* @param name the name of the task
Expand Down Expand Up @@ -528,7 +528,7 @@ private String getApproximateTimeLeft() {
// Attempt to get the time left for all tasks by summing their timeouts
double timeLeft = tasks.stream().mapToDouble(task -> {
// We cannot extract the duration of a task that is not a Task, we will return zero instead of the assumption
// as they are completely out of our control and we don't even know how they function
// as they are completely out of our control, and we don't even know how they function
Measure<Time> timeout = task.timeout;
// We have to approximate and guess as we cannot determine the duration of a task that is infinite
if (timeout.magnitude() == 0.0) {
Expand Down Expand Up @@ -705,7 +705,7 @@ protected final void setOpModes(@Nullable Object... selectableOpModes) {
*
* @param selectedOpMode the OpMode selected by the user, if applicable. Will be NULL if the user does not select an OpMode (and OpModes were available).
* Will be an empty reference if {@link #setOpModes(Object...)} returned null (no OpModes to select).
* @param selectedButton the button selected by the user. Will be Controls.NONE if no selection is made or given.
* @param selectedButton the button selected by the user. Will be {@link Controls#NONE} if no selection is made or given.
* @see #add(Task)
*/
protected abstract void onReady(@Nullable Reference<?> selectedOpMode, @NonNull Controls selectedButton);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,11 +116,11 @@ abstract class BunyipsOpMode : BOMInternal() {
* The instance of the current [BunyipsOpMode]. This is set automatically by the [BunyipsOpMode] lifecycle.
* This can be used instead of dependency injection to access the current OpMode, as it is a singleton.
*
* `BunyipsComponent` (and derivatives `Task`, `BunyipsSubsystem`, etc) internally use this to grant access
* `BunyipsComponent` (and derivatives `Task`, `BunyipsSubsystem`, etc.) internally use this to grant access
* to the current BunyipsOpMode through the `opMode` property.
*
* If you choose to access the current OpMode through this property, you must ensure that the OpMode
* is actively running, otherwise this property will be null and you will raise a full-crashing exception.
* is actively running, otherwise this property will be null, and you will raise a full-crashing exception.
*
* @throws UninitializedPropertyAccessException If a [BunyipsOpMode] is not running, this exception will be raised.
* @return The instance of the current [BunyipsOpMode].
Expand Down Expand Up @@ -174,7 +174,7 @@ abstract class BunyipsOpMode : BOMInternal() {
/**
* Run code in a loop AFTER [onInit] has completed, until start is pressed on the Driver Station
* and the init-task ([setInitTask]) is done. The boolean returned by this method will indicate the status
* of the imit-loop, if it returns true, the init-loop will finish early.
* of the init-loop, if it returns true, the init-loop will finish early.
*
* If not implemented and no init-task is defined, the OpMode will continue on as normal and wait for start.
*/
Expand Down Expand Up @@ -531,7 +531,7 @@ abstract class BunyipsOpMode : BOMInternal() {
}

/**
* Set a task (exposed as minimum type of an [Action]) that will run as an init-task. This will run
* Set a task (exposed as minimum type of [Action]) that will run as an init-task. This will run
* after your [onInit] has completed, allowing you to initialise hardware first.
* This is an optional method, and runs alongside [onInitLoop].
*
Expand All @@ -558,7 +558,7 @@ abstract class BunyipsOpMode : BOMInternal() {
* a subsystem or task.
*
* This method is public to allow you to add looping code from [RobotConfig], [Task], and other contexts.
* The runnables will run in the in the order they were added, and duplicate Runnable instances will be ignored.
* The runnables will run in the order they were added, and duplicate Runnable instances will be ignored.
*/
fun onActiveLoop(vararg runnables: Runnable) {
// Using a set to not have multiple instances of the same Runnable
Expand All @@ -572,7 +572,7 @@ abstract class BunyipsOpMode : BOMInternal() {
* a subsystem or task.
*
* This method is public to allow you to add looping code from [RobotConfig], [Task], and other contexts.
* This runnable will run in the in the order they were added, and duplicate Runnable instances will be ignored.
* This runnable will run in the order they were added, and duplicate Runnable instances will be ignored.
*/
fun onActiveLoop(runnable: Runnable) {
this.runnables.add(runnable)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -220,7 +220,7 @@ public final void disable() {
}

/**
* Re-enable a subsystem if it was previously disabled via a disable() call.
* Re-enable a subsystem if it was previously disabled via a {@link #disable} call.
* This method will no-op if the assertion from {@link #assertParamsNotNull(Object...)} failed.
*/
public final void enable() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ public Scheduler.ScheduledTask always() {
* the automatic collection of {@link BunyipsSubsystem}s, and allows you to determine which subsystems will be managed for
* this OpMode.
* <p>
* For most cases, using this method is not required and all you need to do is construct your subsystems and they
* For most cases, using this method is not required and all you need to do is construct your subsystems, and they
* will be managed automatically. This method is for advanced cases where you don't want this behaviour to happen.
*
* @param subsystems the restrictive list of subsystems to be managed and updated by the scheduler
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ public boolean getFallingEdge() {
}

/**
* Creates a new Condition that is the logical OR of this Condition and another @link BooleanSupplier}.
* Creates a new Condition that is the logical OR of this Condition and another {@link BooleanSupplier}.
*
* @param other The other {@link BooleanSupplier} to OR with.
* @return A new Condition that is the logical OR of this Condition and the other {@link BooleanSupplier}.
Expand All @@ -154,7 +154,7 @@ public Condition or(@NonNull BooleanSupplier other) {
}

/**
* Creates a new Condition that is the logical AND of this Condition and anot @link BooleanSupplier}.
* Creates a new Condition that is the logical AND of this Condition and another {@link BooleanSupplier}.
*
* @param other The other {@link BooleanSupplier} to AND with.
* @return A new Condition that is the logical AND of this Condition and the other {@link BooleanSupplier}.
Expand All @@ -165,7 +165,7 @@ public Condition and(@NonNull BooleanSupplier other) {
}

/**
* Creates a new Condition that is the logical XOR of this Condition and anot @link BooleanSupplier}.
* Creates a new Condition that is the logical XOR of this Condition and another {@link BooleanSupplier}.
*
* @param other The other {@link BooleanSupplier} to XOR with.
* @return A new Condition that is the logical XOR of this Condition and the other {@link BooleanSupplier}.
Expand Down
Loading

0 comments on commit aa1bcde

Please sign in to comment.