diff --git a/Path/src/main/java/com/technototes/path/subsystem/PathingMecanumDrivebaseSubsystem.java b/Path/src/main/java/com/technototes/path/subsystem/PathingMecanumDrivebaseSubsystem.java index 20c7b813..fecd2046 100644 --- a/Path/src/main/java/com/technototes/path/subsystem/PathingMecanumDrivebaseSubsystem.java +++ b/Path/src/main/java/com/technototes/path/subsystem/PathingMecanumDrivebaseSubsystem.java @@ -123,10 +123,10 @@ public PathingMecanumDrivebaseSubsystem( c.getDouble(WheelBase.class), c.getDouble(LateralMult.class) ); - leftFront = fl.getDevice(); - leftRear = rl.getDevice(); - rightRear = rr.getDevice(); - rightFront = fr.getDevice(); + leftFront = fl.getRawMotor(DcMotorEx.class); + leftRear = rl.getRawMotor(DcMotorEx.class); + rightRear = rr.getRawMotor(DcMotorEx.class); + rightFront = fr.getRawMotor(DcMotorEx.class); motors = Arrays.asList(leftFront, leftRear, rightRear, rightFront); diff --git a/Path/src/main/java/com/technototes/path/subsystem/TwoDeadWheelLocalizer.java b/Path/src/main/java/com/technototes/path/subsystem/TwoDeadWheelLocalizer.java new file mode 100644 index 00000000..75e5b7bd --- /dev/null +++ b/Path/src/main/java/com/technototes/path/subsystem/TwoDeadWheelLocalizer.java @@ -0,0 +1,104 @@ +package com.technototes.path.subsystem; + +import static com.technototes.path.subsystem.DeadWheelConstants.EncoderOverflow; +import static com.technototes.path.subsystem.DeadWheelConstants.ForwardOffset; +import static com.technototes.path.subsystem.DeadWheelConstants.GearRatio; +import static com.technototes.path.subsystem.DeadWheelConstants.LateralDistance; +import static com.technototes.path.subsystem.DeadWheelConstants.TicksPerRev; +import static com.technototes.path.subsystem.DeadWheelConstants.WheelRadius; + +import androidx.annotation.NonNull; +import com.acmerobotics.roadrunner.geometry.Pose2d; +import com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer; +import com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer; +import com.technototes.library.hardware.sensor.IMU; +import com.technototes.library.hardware.sensor.encoder.MotorEncoder; +import com.technototes.library.subsystem.Subsystem; +import java.util.Arrays; +import java.util.List; +import java.util.function.DoubleSupplier; + +/* + * Sample tracking wheel localizer implementation assuming a standard configuration: + * + * /---------------\ + * | ____ | + * | ---- | + * | || ^ | + * | ||<- lr | | + * | fb | + * | | + * \---------------/ + * + * COMPLETELY UNTESTED!! + */ +public class TwoDeadWheelLocalizer extends TwoTrackingWheelLocalizer implements Subsystem { + + protected MotorEncoder leftrightEncoder, frontbackEncoder; + protected DoubleSupplier headingSupplier; + protected double lateralDistance, forwardOffset, gearRatio, wheelRadius, ticksPerRev; + + protected boolean encoderOverflow; + + public TwoDeadWheelLocalizer(IMU imu, MotorEncoder lr, MotorEncoder fb, DeadWheelConstants constants) { + super( + Arrays.asList( + new Pose2d(0, constants.getDouble(LateralDistance.class), 0), // left + new Pose2d(constants.getDouble(ForwardOffset.class), 0, Math.toRadians(90)) // front + ) + ); + leftrightEncoder = lr; + frontbackEncoder = fb; + headingSupplier = () -> imu.gyroHeading(); + + lateralDistance = constants.getDouble(LateralDistance.class); + forwardOffset = constants.getDouble(ForwardOffset.class); + encoderOverflow = constants.getBoolean(EncoderOverflow.class); + gearRatio = constants.getDouble(GearRatio.class); + ticksPerRev = constants.getDouble(TicksPerRev.class); + wheelRadius = constants.getDouble(WheelRadius.class); + } + + public double encoderTicksToInches(double ticks) { + return ((getWheelRadius() * 2 * Math.PI * getGearRatio() * ticks) / getTicksPerRev()); + } + + @NonNull + @Override + public List getWheelPositions() { + return Arrays.asList( + encoderTicksToInches(leftrightEncoder.getCurrentPosition()), + encoderTicksToInches(frontbackEncoder.getCurrentPosition()) + ); + } + + @NonNull + @Override + public List getWheelVelocities() { + // TODO: If your encoder velocity can exceed 32767 counts / second (such as the REV Through Bore and other + // competing magnetic encoders), change Encoder.getRawVelocity() to Encoder.getCorrectedVelocity() to enable a + // compensation method + + return Arrays.asList( + encoderTicksToInches(leftrightEncoder.getCorrectedVelocity()), + encoderTicksToInches(frontbackEncoder.getCorrectedVelocity()) + ); + } + + public double getTicksPerRev() { + return ticksPerRev; + } + + public double getWheelRadius() { + return wheelRadius; + } + + public double getGearRatio() { + return gearRatio; + } + + @Override + public double getHeading() { + return headingSupplier.getAsDouble(); + } +} diff --git a/Path/src/main/java/com/technototes/path/trajectorysequence/TrajectoryPath.java b/Path/src/main/java/com/technototes/path/trajectorysequence/TrajectoryPath.java new file mode 100644 index 00000000..35941384 --- /dev/null +++ b/Path/src/main/java/com/technototes/path/trajectorysequence/TrajectoryPath.java @@ -0,0 +1,176 @@ +package com.technototes.path.trajectorysequence; + +import com.acmerobotics.roadrunner.geometry.Pose2d; +import com.technototes.path.geometry.ConfigurablePose; +import com.technototes.path.geometry.ConfigurablePoseD; +import java.util.function.Function; + +public interface TrajectoryPath extends Function, TrajectorySequence> { + /** + * Create a spline between two poses + * + * @param start The beginning of a spline + * @param end The end of a spline + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath splineTo(ConfigurablePose start, ConfigurablePose end) { + return b -> b.apply(start.toPose()).splineTo(end.toVec(), end.getHeading()).build(); + } + + /** + * Create a spline between two poses + * + * @param start The beginning of a spline + * @param end The end of a spline + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath splineTo(ConfigurablePoseD start, ConfigurablePoseD end) { + return b -> b.apply(start.toPose()).splineTo(end.toVec(), end.getHeading()).build(); + } + + /** + * Create a spline between a list of poses + * + * @param start The beginning of a spline + * @param points The remaing points of the spline + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath splinesTo(ConfigurablePoseD start, ConfigurablePoseD... points) { + return b -> { + TrajectorySequenceBuilder bld = b.apply(start.toPose()); + for (ConfigurablePoseD d : points) { + bld = bld.splineTo(d.toVec(), d.getHeading()); + } + return bld.build(); + }; + } + + /** + * Create a spline between a list of poses + * + * @param start The beginning of a spline + * @param points The remaing points of the spline + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath splinesTo(ConfigurablePose start, ConfigurablePose... points) { + return b -> { + TrajectorySequenceBuilder bld = b.apply(start.toPose()); + for (ConfigurablePose d : points) { + bld = bld.splineTo(d.toVec(), d.getHeading()); + } + return bld.build(); + }; + } + + /** + * Create a line between two poses + * + * @param start The beginning of the line + * @param end The end of the line + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath lineTo(ConfigurablePose start, ConfigurablePose end) { + return b -> b.apply(start.toPose()).lineTo(end.toPose().vec()).build(); + } + + /** + * Create a line between two poses + * + * @param start The beginning of the line + * @param end The end of the line + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath lineTo(ConfigurablePoseD start, ConfigurablePoseD end) { + return b -> b.apply(start.toPose()).lineTo(end.toPose().vec()).build(); + } + + /** + * Create a line between a list of poses + * + * @param start The beginning of the line + * @param points The points of the line + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath linesTo(ConfigurablePoseD start, ConfigurablePoseD... points) { + return b -> { + TrajectorySequenceBuilder bld = b.apply(start.toPose()); + for (ConfigurablePoseD d : points) { + bld = bld.lineTo(d.toPose().vec()); + } + return bld.build(); + }; + } + + /** + * Create a line between a list of poses + * + * @param start The beginning of the line + * @param points The points of the line + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath linesTo(ConfigurablePose start, ConfigurablePose... points) { + return b -> { + TrajectorySequenceBuilder bld = b.apply(start.toPose()); + for (ConfigurablePose d : points) { + bld = bld.lineTo(d.toPose().vec()); + } + return bld.build(); + }; + } + + /** + * Create a line between two poses on a specific linear heading + * + * @param start The beginning of the line + * @param end The end of the line + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath lineToLinearHeading(ConfigurablePose start, ConfigurablePose end) { + return b -> b.apply(start.toPose()).lineToLinearHeading(end.toPose()).build(); + } + + /** + * Create a line between two poses on a specific linear heading + * + * @param start The beginning of the line + * @param end The end of the line + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath lineToLinearHeading(ConfigurablePoseD start, ConfigurablePoseD end) { + return b -> b.apply(start.toPose()).lineToLinearHeading(end.toPose()).build(); + } + + /** + * Create a set of lines between a list of poses on a specific linear heading + * + * @param start The beginning of the line + * @param points The list of points in the line + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath linesToLinearHeadings(ConfigurablePoseD start, ConfigurablePoseD... points) { + return b -> { + TrajectorySequenceBuilder bld = b.apply(start.toPose()); + for (ConfigurablePoseD d : points) { + bld = bld.lineToLinearHeading(d.toPose()); + } + return bld.build(); + }; + } + + /** + * Create a set of lines between a list of poses on a specific linear heading + * + * @param start The beginning of the line + * @param points The list of points in the line + * @return A function that takes a 'start' location and returns a TrajectorySequenceBuilder + */ + static TrajectoryPath linesToLinearHeadings(ConfigurablePose start, ConfigurablePose... points) { + return b -> { + TrajectorySequenceBuilder bld = b.apply(start.toPose()); + for (ConfigurablePose d : points) { + bld = bld.lineToLinearHeading(d.toPose()); + } + return bld.build(); + }; + } +} diff --git a/RobotLibrary/src/main/java/com/technototes/library/command/CommandBase.java b/RobotLibrary/src/main/java/com/technototes/library/command/CommandBase.java deleted file mode 100644 index 0051d4b6..00000000 --- a/RobotLibrary/src/main/java/com/technototes/library/command/CommandBase.java +++ /dev/null @@ -1,26 +0,0 @@ -package com.technototes.library.command; - -/** - * Command base class for people who like parity with wpilib - *

- * Deprecated because I don't care about wpilib in the least - */ -@Deprecated -public abstract class CommandBase implements Command { - - /** - * Execute the command - */ - @Override - public void execute() {} - - /** - * Is this command finished - * - * @return - */ - @Override - public boolean isFinished() { - return false; - } -} diff --git a/RobotLibrary/src/main/java/com/technototes/library/command/CommandScheduler.java b/RobotLibrary/src/main/java/com/technototes/library/command/CommandScheduler.java index 94ea925e..60e4d542 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/command/CommandScheduler.java +++ b/RobotLibrary/src/main/java/com/technototes/library/command/CommandScheduler.java @@ -23,33 +23,28 @@ */ public final class CommandScheduler { - private final Map commandMap; - private final Map> requirementMap; - private final Map defaultMap; + private static final Map commandMap = new HashMap<>(); + private static final Map> requirementMap = new HashMap<>(); + private static final Map defaultMap = new HashMap<>(); - private final Set registered; + private static final Set registered = new LinkedHashSet<>(); - private CommandOpMode opMode; + private static CommandOpMode opMode; /** * Set the scheduler's opmode * * @param c the opmode - * @return the CommandScheduler (useful for chaining) */ - public CommandScheduler setOpMode(CommandOpMode c) { + public static void setOpMode(CommandOpMode c) { opMode = c; - return this; } /** * Forcefully halt the opmode - * - * @return the CommandScheduler (useful for chaining) */ - public CommandScheduler terminateOpMode() { + public static void terminateOpMode() { opMode.terminate(); - return this; } /** @@ -57,73 +52,70 @@ public CommandScheduler terminateOpMode() { * * @return elapsed time since opmode was started, in seconds */ - public double getOpModeRuntime() { + public static double getOpModeRuntime() { return opMode.getOpModeRuntime(); } - // The Singleton CommandScheduler - private static CommandScheduler instance; - /** - * Get (or create) the singleton CommandScheduler object - * - * @return The CommandScheduler singleton + * Reset the scheduler... */ - public static synchronized CommandScheduler getInstance() { - if (instance == null) { - instance = new CommandScheduler(); - } - return instance; + public static void resetScheduler() { + Command.clear(); } /** - * Alex had a comment "be careful with this" and he's not wrong. - * This removes the old Singleton and creates a new one. That's pretty dangerous... + * Schedule a command to run (just use "schedule") * - * @return a *new* singleton object (which makes very little sense) + * @param command the command to schedule */ - public static synchronized CommandScheduler resetScheduler() { - instance = null; - Command.clear(); - return getInstance(); + public static void scheduleOnce(Command command) { + schedule(command); } - private CommandScheduler() { - commandMap = new HashMap<>(); - requirementMap = new HashMap<>(); - defaultMap = new HashMap<>(); - registered = new LinkedHashSet<>(); + /** + * Schedule a command to run during a particular OpModeState + * You can just use scheduleForState instead... + * + * @param command the command to schedule + * @param state the state during which the command should be scheduled + */ + public static void scheduleOnceForState(Command command, CommandOpMode.OpModeState state) { + scheduleForState(command, state); } /** - * Schedule a command to run + * Schedules a command to be run during Run and End states, all the time. + * This is called "Schedule for Joystick" because joysticks don't really have a + * condition you might consider 'useful for triggering', so the command + * just runs repeatedly. This adds the requirement that the BooleanSupplier function + * is also true for the command to be run. * - * @param command the command to schedule - * @return the CommandScheduler (useful for chaining) + * @param command The command to run repeatedly + * @param supplier The condition which must also be true to run the command */ - public CommandScheduler schedule(Command command) { - return schedule(command, () -> true); + public static void scheduleJoystick(Command command, BooleanSupplier supplier) { + scheduleForState(command, supplier, CommandOpMode.OpModeState.RUN, CommandOpMode.OpModeState.END); } /** - * Schedule a command to run + * Schedules a command to be run during Run and End states, all the time. + * This is called "Schedule for Joystick" because joysticks don't really have a + * condition you might consider 'useful for triggering', so the command + * just runs repeatedly * - * @param command the command to schedule - * @return the CommandScheduler (useful for chaining) + * @param command The command to run repeatedly. */ - public CommandScheduler scheduleOnce(Command command) { - return schedule(command); + public static void scheduleJoystick(Command command) { + scheduleForState(command, CommandOpMode.OpModeState.RUN, CommandOpMode.OpModeState.END); } /** - * Schedule a command to run during a particular OpModeState + * Schedule a command to run * * @param command the command to schedule - * @param state the state during which the command should be scheduled - * @return the CommandScheduler (useful for chaining) */ - public CommandScheduler scheduleOnceForState(Command command, CommandOpMode.OpModeState state) { - return scheduleForState(command, state); + public static void schedule(Command command) { + schedule(command, () -> true); } /** @@ -134,10 +126,9 @@ public CommandScheduler scheduleOnceForState(Command command, CommandOpMode.OpMo * * @param command The command to run * @param supplier The condition which also must be true to run the command - * @return The CommandScheduler singleton for chaining */ - public CommandScheduler scheduleInit(Command command, BooleanSupplier supplier) { - return scheduleForState(command, supplier, CommandOpMode.OpModeState.INIT); + public static void scheduleInit(Command command, BooleanSupplier supplier) { + scheduleForState(command, supplier, CommandOpMode.OpModeState.INIT); } /** @@ -146,38 +137,9 @@ public CommandScheduler scheduleInit(Command command, BooleanSupplier supplier) * drive team ensure that the robot is appropriately positioned on the field. * * @param command The command to run - * @return The CommandScheduler singleton for chaining - */ - public CommandScheduler scheduleInit(Command command) { - return scheduleForState(command, () -> true, CommandOpMode.OpModeState.INIT); - } - - /** - * Schedules a command to be run during Run and End states, all the time. - * This is called "Schedule for Joystick" because joysticks don't really have a - * condition you might consider 'useful for triggering', so the command - * just runs repeatedly. This adds the requirement that the BooleanSupplier function - * is also true for the command to be run. - * - * @param command The command to run repeatedly - * @param supplier The condition which must also be true to run the command - * @return The CommandScheduler singleton for chaining - */ - public CommandScheduler scheduleJoystick(Command command, BooleanSupplier supplier) { - return scheduleForState(command, supplier, CommandOpMode.OpModeState.RUN, CommandOpMode.OpModeState.END); - } - - /** - * Schedules a command to be run during Run and End states, all the time. - * This is called "Schedule for Joystick" because joysticks don't really have a - * condition you might consider 'useful for triggering', so the command - * just runs repeatedly - * - * @param command The command to run repeatedly. - * @return The CommandScheduler singleton for chaining */ - public CommandScheduler scheduleJoystick(Command command) { - return scheduleForState(command, CommandOpMode.OpModeState.RUN, CommandOpMode.OpModeState.END); + public static void scheduleInit(Command command) { + scheduleForState(command, () -> true, CommandOpMode.OpModeState.INIT); } /** @@ -187,14 +149,13 @@ public CommandScheduler scheduleJoystick(Command command) { * @param command The command to run * @param states The list of states to schedule the command * @param supplier The function to determin in the command should be scheduled - * @return The CommandScheduler singleton for chaining */ - public CommandScheduler scheduleForState( + public static void scheduleForState( Command command, BooleanSupplier supplier, CommandOpMode.OpModeState... states ) { - return schedule( + schedule( command.cancelUpon(() -> !opMode.getOpModeState().isState(states)), () -> supplier.getAsBoolean() && opMode.getOpModeState().isState(states) ); @@ -205,10 +166,9 @@ public CommandScheduler scheduleForState( * * @param command The command to run * @param states The list of states to schedule the command - * @return The CommandScheduler singleton for chaining */ - public CommandScheduler scheduleForState(Command command, CommandOpMode.OpModeState... states) { - return schedule( + public static void scheduleForState(Command command, CommandOpMode.OpModeState... states) { + schedule( command.cancelUpon(() -> !opMode.getOpModeState().isState(states)), () -> opMode.getOpModeState().isState(states) ); @@ -220,10 +180,9 @@ public CommandScheduler scheduleForState(Command command, CommandOpMode.OpModeSt * * @param dependency The command upon which 'other' depends * @param other The command to schedule when 'dependency' has finished - * @return The CommandScheduler singleton for chaining */ - public CommandScheduler scheduleAfterOther(Command dependency, Command other) { - return schedule(other, dependency::justFinishedNoCancel); + public static void scheduleAfterOther(Command dependency, Command other) { + schedule(other, dependency::justFinishedNoCancel); } /** @@ -232,10 +191,9 @@ public CommandScheduler scheduleAfterOther(Command dependency, Command other) { * * @param dependency The command upon which 'other' depends * @param other The command to schedule when 'dependency' has started - * @return The CommandScheduler singleton for chaining */ - public CommandScheduler scheduleWithOther(Command dependency, Command other) { - return schedule(other, dependency::justStarted); + public static void scheduleWithOther(Command dependency, Command other) { + schedule(other, dependency::justStarted); } /** @@ -245,10 +203,9 @@ public CommandScheduler scheduleWithOther(Command dependency, Command other) { * @param dependency The command upon which 'other' depends * @param other The command to schedule when 'dependency' has finished * @param additionalCondition The additional condition necessary to be true to schedule the 'other' command - * @return The CommandScheduler singleton for chaining */ - public CommandScheduler scheduleAfterOther(Command dependency, Command other, BooleanSupplier additionalCondition) { - return schedule(other, () -> dependency.justFinishedNoCancel() && additionalCondition.getAsBoolean()); + public static void scheduleAfterOther(Command dependency, Command other, BooleanSupplier additionalCondition) { + schedule(other, () -> dependency.justFinishedNoCancel() && additionalCondition.getAsBoolean()); } /** @@ -258,10 +215,9 @@ public CommandScheduler scheduleAfterOther(Command dependency, Command other, Bo * @param dependency The command upon which 'other' depends * @param other The command to schedule when 'dependency' has started * @param additionalCondition The additional condition necessary to be true to schedule the 'other' command - * @return The CommandScheduler singleton for chaining */ - public CommandScheduler scheduleWithOther(Command dependency, Command other, BooleanSupplier additionalCondition) { - return schedule(other, () -> dependency.justStarted() && additionalCondition.getAsBoolean()); + public static void scheduleWithOther(Command dependency, Command other, BooleanSupplier additionalCondition) { + schedule(other, () -> dependency.justStarted() && additionalCondition.getAsBoolean()); } /** @@ -270,27 +226,23 @@ public CommandScheduler scheduleWithOther(Command dependency, Command other, Boo * * @param command The command to be run when others aren't using that subsystem * @param subsystem The subsystem to run the command against when it's unused - * @return The CommandScheduler singleton for chaining */ - public CommandScheduler scheduleDefault(Command command, Subsystem subsystem) { + public static void scheduleDefault(Command command, Subsystem subsystem) { if (command.getRequirements().contains(subsystem)) { defaultMap.put(subsystem, command); schedule(command, () -> getCurrent(subsystem) == command); } else { System.err.println("default commands must require their subsystem: " + command.getClass().toString()); } - return this; } /** * Register a periodic function to be run once each schedule loop * * @param p The Periodic function to run - * @return The CommandScheduler singleton for chaining */ - public CommandScheduler register(Periodic p) { + public static void register(Periodic p) { registered.add(p); - return this; } /** @@ -300,7 +252,7 @@ public CommandScheduler register(Periodic p) { * @return the default command for the subsystem, or null if there is none */ @Nullable - public Command getDefault(Subsystem s) { + public static Command getDefault(Subsystem s) { return opMode.getOpModeState() == CommandOpMode.OpModeState.RUN ? defaultMap.get(s) : null; } @@ -313,7 +265,7 @@ public Command getDefault(Subsystem s) { * command usint the subsystem, nor a default command */ @Nullable - public Command getCurrent(Subsystem s) { + public static Command getCurrent(Subsystem s) { if (requirementMap.get(s) == null) return null; for (Command c : requirementMap.get(s)) { if (c.isRunning()) return c; @@ -327,23 +279,22 @@ public Command getCurrent(Subsystem s) { * * @param command The command to schedule * @param supplier The function that returns true when the command should be run - * @return the CommandScheduler singleton for easy chaining */ - public CommandScheduler schedule(Command command, BooleanSupplier supplier) { + public static void schedule(Command command, BooleanSupplier supplier) { commandMap.put(command, supplier); for (Subsystem s : command.getRequirements()) { + // TODO: Fail if a required subsystem is null, and maybe log something requirementMap.putIfAbsent(s, new LinkedHashSet<>()); requirementMap.get(s).add(command); register(s); } - return this; } /** * This is invoked from inside the CommandOpMode method, during the opCode. * It it the core logic of actually scheduling & running the commands. */ - public void run() { + public static void run() { // For each newly scheduled command, // cancel any existing command that is using the new command's subsystem requirements commandMap.forEach((c1, b) -> { diff --git a/RobotLibrary/src/main/java/com/technototes/library/command/ConditionalCommand.java b/RobotLibrary/src/main/java/com/technototes/library/command/ConditionalCommand.java index 375981db..5676b893 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/command/ConditionalCommand.java +++ b/RobotLibrary/src/main/java/com/technototes/library/command/ConditionalCommand.java @@ -45,7 +45,7 @@ public ConditionalCommand(BooleanSupplier condition) { public ConditionalCommand(BooleanSupplier condition, Command command) { supplier = condition; trueCommand = command; - CommandScheduler.getInstance().scheduleWithOther(this, trueCommand, condition); + CommandScheduler.scheduleWithOther(this, trueCommand, condition); falseCommand = null; } @@ -60,8 +60,8 @@ public ConditionalCommand(BooleanSupplier condition, Command trueC, Command fals supplier = condition; trueCommand = trueC; falseCommand = falseC; - CommandScheduler.getInstance().scheduleWithOther(this, trueCommand, condition); - CommandScheduler.getInstance().scheduleWithOther(this, falseCommand, () -> !condition.getAsBoolean()); + CommandScheduler.scheduleWithOther(this, trueCommand, condition); + CommandScheduler.scheduleWithOther(this, falseCommand, () -> !condition.getAsBoolean()); } @Override diff --git a/RobotLibrary/src/main/java/com/technototes/library/command/ParallelCommandGroup.java b/RobotLibrary/src/main/java/com/technototes/library/command/ParallelCommandGroup.java index ee53b828..2ba12847 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/command/ParallelCommandGroup.java +++ b/RobotLibrary/src/main/java/com/technototes/library/command/ParallelCommandGroup.java @@ -18,7 +18,7 @@ public ParallelCommandGroup(Command... commands) { @Override public void schedule(Command c) { - CommandScheduler.getInstance().scheduleWithOther(this, c); + CommandScheduler.scheduleWithOther(this, c); } /** diff --git a/RobotLibrary/src/main/java/com/technototes/library/command/ParallelDeadlineGroup.java b/RobotLibrary/src/main/java/com/technototes/library/command/ParallelDeadlineGroup.java index 2171a191..7b358279 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/command/ParallelDeadlineGroup.java +++ b/RobotLibrary/src/main/java/com/technototes/library/command/ParallelDeadlineGroup.java @@ -28,7 +28,7 @@ public ParallelDeadlineGroup(Command command, Command... commands) { */ @Override public void schedule(Command c) { - CommandScheduler.getInstance().scheduleWithOther(this, c); + CommandScheduler.scheduleWithOther(this, c); } /** diff --git a/RobotLibrary/src/main/java/com/technototes/library/command/ParallelRaceGroup.java b/RobotLibrary/src/main/java/com/technototes/library/command/ParallelRaceGroup.java index 9d9cd541..bc111b44 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/command/ParallelRaceGroup.java +++ b/RobotLibrary/src/main/java/com/technototes/library/command/ParallelRaceGroup.java @@ -23,7 +23,7 @@ public ParallelRaceGroup(Command... commands) { */ @Override public void schedule(Command c) { - CommandScheduler.getInstance().scheduleWithOther(this, c); + CommandScheduler.scheduleWithOther(this, c); } /** diff --git a/RobotLibrary/src/main/java/com/technototes/library/command/SequentialCommandGroup.java b/RobotLibrary/src/main/java/com/technototes/library/command/SequentialCommandGroup.java index f4f43c1b..c8bfaee0 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/command/SequentialCommandGroup.java +++ b/RobotLibrary/src/main/java/com/technototes/library/command/SequentialCommandGroup.java @@ -27,9 +27,9 @@ public SequentialCommandGroup(Command... commands) { @Override public void schedule(Command c) { if (lastCommand == null) { - CommandScheduler.getInstance().scheduleWithOther(this, c); + CommandScheduler.scheduleWithOther(this, c); } else { - CommandScheduler.getInstance().scheduleAfterOther(lastCommand, c); + CommandScheduler.scheduleAfterOther(lastCommand, c); } lastCommand = c; } diff --git a/RobotLibrary/src/main/java/com/technototes/library/command/SimpleCommand.java b/RobotLibrary/src/main/java/com/technototes/library/command/SimpleCommand.java new file mode 100644 index 00000000..92515cf3 --- /dev/null +++ b/RobotLibrary/src/main/java/com/technototes/library/command/SimpleCommand.java @@ -0,0 +1,24 @@ +package com.technototes.library.command; + +import com.technototes.library.subsystem.Subsystem; +import java.util.function.Consumer; + +public class SimpleCommand implements Command { + + Runnable method; + + public SimpleCommand(Runnable m) { + super(); + method = m; + } + + public SimpleCommand(Consumer m, T arg) { + super(); + method = () -> m.accept(arg); + } + + @Override + public void execute() { + method.run(); + } +} diff --git a/RobotLibrary/src/main/java/com/technototes/library/command/SimpleRequiredCommand.java b/RobotLibrary/src/main/java/com/technototes/library/command/SimpleRequiredCommand.java new file mode 100644 index 00000000..213acdf7 --- /dev/null +++ b/RobotLibrary/src/main/java/com/technototes/library/command/SimpleRequiredCommand.java @@ -0,0 +1,30 @@ +package com.technototes.library.command; + +import com.technototes.library.subsystem.Subsystem; +import java.util.function.BiConsumer; +import java.util.function.Consumer; + +public class SimpleRequiredCommand implements Command { + + T sub; + Consumer method; + + public SimpleRequiredCommand(T s, Consumer m) { + super(); + sub = s; + method = m; + addRequirements(sub); + } + + public SimpleRequiredCommand(T s, BiConsumer m, U arg) { + super(); + sub = s; + method = subsys -> m.accept(subsys, arg); + addRequirements(sub); + } + + @Override + public void execute() { + method.accept(sub); + } +} diff --git a/RobotLibrary/src/main/java/com/technototes/library/control/ButtonBase.java b/RobotLibrary/src/main/java/com/technototes/library/control/ButtonBase.java index 07164d6b..cdb643cd 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/control/ButtonBase.java +++ b/RobotLibrary/src/main/java/com/technototes/library/control/ButtonBase.java @@ -115,26 +115,48 @@ public boolean isInverseToggled() { */ @Override public boolean getAsBoolean() { + // Alex had to get some of that sweet, sweet exclusive or operator... + // For the non-bit-twiddly among us, this is (bs.get() != inverted) && isEnabled() + // Or, verbally: flip the booleanSupplier if it's inverted, and it's only true if + // it's also enabled... return booleanSupplier.getAsBoolean() ^ inverted && isEnabled(); } + /** + * Inverts the button, such that "isPressed" and "isReleased" are opposite, along with everything + * that entails + * + * @param invert Inversion value (true inverts, false leaves the values as is) + * @return the ButtonBase object + */ @Override public ButtonBase setInverted(boolean invert) { inverted = invert; return this; } + /** + * @return True if the button is inverted (pressed registers as released, etc...) + */ @Override public boolean getInverted() { return inverted; } + /** + * Enable or disable the button + * @param enable True for enabled, false for disabled + * @return + */ @Override public ButtonBase setEnabled(boolean enable) { enabled = enable; return this; } + /** + * @return True if the button is enabled + */ @Override public boolean isEnabled() { return enabled; diff --git a/RobotLibrary/src/main/java/com/technototes/library/control/CommandGamepad.java b/RobotLibrary/src/main/java/com/technototes/library/control/CommandGamepad.java index 00f93fa8..8ff15a73 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/control/CommandGamepad.java +++ b/RobotLibrary/src/main/java/com/technototes/library/control/CommandGamepad.java @@ -44,12 +44,12 @@ public CommandGamepad scheduleDpad(BiConsumer f) { } public CommandGamepad scheduleStick(Stick s, BiFunction f) { - CommandScheduler.getInstance().scheduleJoystick(f.apply(s.getXAxis(), s.getXAxis())); + CommandScheduler.scheduleJoystick(f.apply(s.getXAxis(), s.getXAxis())); return this; } public CommandGamepad scheduleStick(Stick s, BiConsumer f) { - CommandScheduler.getInstance().scheduleJoystick(() -> f.accept(s.getXAxis(), s.getXAxis())); + CommandScheduler.scheduleJoystick(() -> f.accept(s.getXAxis(), s.getXAxis())); return this; } diff --git a/RobotLibrary/src/main/java/com/technototes/library/control/CommandInput.java b/RobotLibrary/src/main/java/com/technototes/library/control/CommandInput.java index 750df3de..fc7afd8f 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/control/CommandInput.java +++ b/RobotLibrary/src/main/java/com/technototes/library/control/CommandInput.java @@ -76,7 +76,7 @@ default T whilePressedContinuous(Command command) { } /** - * Schdule the command to be run when the input is released, but only once! + * Schedule the command to be run when the input is released, but only once! * * @param command The command to be run * @return The CommandInput<T> instance @@ -145,7 +145,7 @@ default T whileInverseToggled(Command command) { * @return The CommandInput<T> instance */ default T schedule(BooleanSupplier condition, Command command) { - CommandScheduler.getInstance().scheduleJoystick(command, condition); + CommandScheduler.scheduleJoystick(command, condition); return getInstance(); } @@ -164,6 +164,8 @@ default T schedule(Command command) { * 'press' will be executed once when the input is pressed. * 'release' will be executed once when the input is released. * + * You could just use button.whenPressed(press).whenRelease(release) + * * @param press The command to run on Press * @param release The command to run on Release * @return The CommandInput<T> instance @@ -176,7 +178,9 @@ default T whenPressedReleased(Command press, Command release) { /** * For scheduling a pair commands for while the input is pressed and released. * 'press' will be executed over & over while the input is pressed. - * 'release' will be exeucted over & over while the input is released. + * 'release' will be executed over & over while the input is released. + * + * Just use button.whilePressed(...).whileReleased(...) * * @param press The command to run on Press * @param release The command to run on Release @@ -191,6 +195,9 @@ default T whilePressedReleased(Command press, Command release) { * For scheduling a pair of "opposite" commands for toggling when something * is or is not being toggled * + * For non-command (method ref) usage, just use + * button.whenToggled(toggled).whenInverseToggled(notToggled) + * * @param toggle The command to run when the input flips states * @param itoggle The command to run when the input has not changed states * @return The CommandInput<T> instance diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/HardwareDevice.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/HardwareDevice.java index 6205b678..be850c7d 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/HardwareDevice.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/HardwareDevice.java @@ -9,7 +9,6 @@ * @param The class for the default device (ones found in ftcsdk) * @author Alex Stedman */ -@Deprecated @SuppressWarnings("unused") public abstract class HardwareDevice { diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/HardwareDeviceGroup.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/HardwareDeviceGroup.java index 509f884b..802e135b 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/HardwareDeviceGroup.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/HardwareDeviceGroup.java @@ -1,7 +1,9 @@ package com.technototes.library.hardware; +import com.technototes.library.hardware.motor.Motor; import java.util.Arrays; import java.util.List; +import java.util.function.Consumer; /** * Interface for hardware device groups @@ -10,7 +12,6 @@ * * @author Alex Stedman */ -@Deprecated @SuppressWarnings("unused") public interface HardwareDeviceGroup { /** @@ -20,7 +21,7 @@ public interface HardwareDeviceGroup { */ T[] getFollowers(); - default List getFollowerist() { + default List getFollowerList() { return Arrays.asList(getFollowers()); } @@ -35,22 +36,20 @@ default List getAllDeviceList() { return Arrays.asList(getAllDevices()); } - /** - * Propogate actions across the followers - *

- * Note to self: Alex couldn't spell :) - * - * @param value the value to propogate - */ - @Deprecated - default void propogate(double value) {} - /** * Propagate actions across the followers - *

- * Note to self: Alex couldn't spell :) * - * @param value the value to propagate + * @param func the action to propagate */ - default void propagate(double value) {} + default void propagate(Consumer func) { + for (T obj : getFollowers()) { + func.accept(obj); + } + } + + T getDeviceNum(int i); + + default int getDeviceCount() { + return getFollowers().length + 1; + } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/Sensored.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/Sensored.java index 81d43481..905ab470 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/Sensored.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/Sensored.java @@ -10,7 +10,6 @@ * * @author Alex Stedman */ -@Deprecated @SuppressWarnings("unused") public interface Sensored extends DoubleSupplier { /** diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/Speaker.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/Speaker.java index 179f17d9..9fd0780c 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/Speaker.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/Speaker.java @@ -9,7 +9,8 @@ /** * There's just no possible way I care about this. I think there are rules about *not* playing - * anything through the speaker now, anyway. This is going away. + * anything through the speaker now, anyway. This is going away. (The rules were created because + * of Alex, if I recall correctly...) */ @Deprecated public class Speaker { diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/CRServo.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/CRServo.java new file mode 100644 index 00000000..4b508e58 --- /dev/null +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/CRServo.java @@ -0,0 +1,36 @@ +package com.technototes.library.hardware.motor; + +import com.technototes.library.hardware.HardwareDevice; +import java.io.InvalidClassException; +import java.util.function.Supplier; + +/** + * This is for "continuous rotation" servos. They work, unfortunately, like motors + * without encoders: You can set a power (from 0 to 1, typically, with .5 as "stop") and the + * servo will spin in the direct, at the provided speed... + * + * Not Yet Implemented! + * TODO: Implement this + */ +public class CRServo extends HardwareDevice implements Supplier { + + public CRServo(com.qualcomm.robotcore.hardware.CRServo device, String deviceName) throws InvalidClassException { + super(device, deviceName); + throw new InvalidClassException("com.technototes.library.hardware.motor.CRServo", "Not Yet Implemented"); + } + + protected CRServo(String deviceName) throws InvalidClassException { + super(deviceName); + throw new InvalidClassException("com.technototes.library.hardware.motor.CRServo", "Not Yet Implemented"); + } + + @Override + public String LogLine() { + return null; + } + + @Override + public Double get() { + return null; + } +} diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/EncodedMotor.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/EncodedMotor.java index ae726fba..bf52cee5 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/EncodedMotor.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/EncodedMotor.java @@ -119,28 +119,30 @@ public EncodedMotor setRunMode(DcMotor.RunMode m) { } /** - * Set the Inverted state for the motor. WARNING: THIS IS BACKWARD TO WHAT YOU MIGHT THINK! - * True - Motor goes *forward*. False - motor goes *reverse*. - *

- * This is overridden so it can return an EncodedMotor, and not just a Motor - * - * @param invert true for forward, false for reverse (probably not what you were expecting) - * @return The motor (for chaining) + * Set the motor to go *backward* */ @Override - public EncodedMotor setInverted(boolean invert) { - super.setInverted(invert); + public EncodedMotor setBackward() { + super.setBackward(); return this; } /** - * Invert the motor (toggle inversion) - * - * @return The motor (for chaining) + * Set the motor to go *forward* */ @Override - public EncodedMotor invert() { - return setInverted(!getInverted()); + public EncodedMotor setForward() { + super.setForward(); + return this; + } + + /** + * Set the motor to go in a particular direction + */ + @Override + public EncodedMotor setDirection(DcMotorSimple.Direction dir) { + super.setDirection(dir); + return this; } /** @@ -289,4 +291,10 @@ public EncodedMotor coast() { public EncodedMotor setLimits(double mi, double ma) { return (EncodedMotor) super.setLimits(mi, ma); } + + // Ah, Java, you're such a hideous language... + public U getRawMotor(Class type) { + T device = getRawDevice(); + return (device != null && type.isInstance(device)) ? type.cast(device) : null; + } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/EncodedMotorGroup.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/EncodedMotorGroup.java index 6931cff9..77c92ca2 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/EncodedMotorGroup.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/EncodedMotorGroup.java @@ -3,56 +3,72 @@ import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.technototes.library.hardware.HardwareDeviceGroup; -/** Class for encoded motor groups +/** + * Class for encoded motor groups + * * @author Alex Stedman */ @SuppressWarnings("unused") public class EncodedMotorGroup extends EncodedMotor - implements HardwareDeviceGroup> { + implements HardwareDeviceGroup> { - private final Motor[] followers; + private final EncodedMotor[] followers; - /** Create an encoded motor groupM + /** + * Create an encoded motor groupM * - * @param leader The Lead motor + * @param leader The Lead motor * @param followers The following motors */ - public EncodedMotorGroup(EncodedMotor leader, Motor... followers) { + public EncodedMotorGroup(EncodedMotor leader, EncodedMotor... followers) { super(leader.getDevice()); this.followers = followers; } @Override - public Motor[] getFollowers() { + public EncodedMotor[] getFollowers() { return followers; } @Override - public Motor[] getAllDevices() { - Motor[] m = new Motor[followers.length + 1]; + public EncodedMotor[] getAllDevices() { + EncodedMotor[] m = new EncodedMotor[followers.length + 1]; m[0] = this; System.arraycopy(followers, 0, m, 1, m.length - 1); return m; } - @Override - public void propogate(double value) { - for (Motor m : followers) { - m.setSpeed(value); - } - } - @Override public void setVelocity(double tps) { super.setVelocity(tps); - propogate(super.getSpeed()); + propagate(obj -> obj.setVelocity(tps)); + } + + public void setVelocities(double... tps) { + for (int i = 0; i < tps.length && i < getDeviceCount(); i++) { + getDeviceNum(i).setVelocity(tps[i]); + } } @Override public boolean setPosition(double ticks, double speed) { - boolean b = super.setPosition(ticks, speed); - propogate(super.getSpeed()); + boolean b = true; + for (int i = 0; i < getDeviceCount(); i++) { + b = getDeviceNum(i).setPosition(ticks, speed) && b; + } return b; } + + public boolean setPositions(double... ticks_then_speeds) { + boolean b = true; + for (int i = 0; i < ticks_then_speeds.length / 2 && i < getDeviceCount(); i++) { + b = getDeviceNum(i).setPosition(ticks_then_speeds[i * 2], ticks_then_speeds[i * 2 + 1]) && b; + } + return b; + } + + public EncodedMotor getDeviceNum(int i) { + return (i == 0) ? this : followers[i - 1]; + } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/Motor.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/Motor.java index e3bae9fa..eac04003 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/Motor.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/Motor.java @@ -3,7 +3,6 @@ import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.util.Range; -import com.technototes.library.general.Invertable; import com.technototes.library.hardware.HardwareDevice; import java.util.function.Supplier; @@ -14,11 +13,8 @@ * @author Alex Stedman */ @SuppressWarnings("unused") -public class Motor - extends HardwareDevice - implements Invertable>, Supplier { +public class Motor extends HardwareDevice implements Supplier { - private boolean invert = false; private double min = -1, max = 1; /** @@ -47,61 +43,81 @@ public Motor(String deviceName) { * @return The Motor (for chaining) */ public Motor setLimits(double mi, double ma) { - min = Range.clip(mi, -1, 1); - max = Range.clip(ma, -1, 1); + mi = Range.clip(mi, -1, 1); + ma = Range.clip(ma, -1, 1); + min = Math.min(mi, ma); + max = Math.max(mi, ma); return this; } /** - * Returns whether the motor is inverted. WARNING: THIS RETURNS TRUE FOR A "FORWARD" SETTING! - * - * @return True for inverted (forward) false for not inverted (reverse) + * Returns the DcMotorSimple.Direction the motor is traveling */ - @Override - public boolean getInverted() { - return invert; + public DcMotorSimple.Direction getDirection() { + return getDevice().getDirection(); } /** - * Set the Inverted state for the motor. WARNING: THIS IS BACKWARD TO WHAT YOU MIGHT THINK! - * True - Motor goes *forward*. False - motor goes *reverse*. - * - * @param inv true for forward, false for reverse (probably not what you were expecting) - * @return The motor (for chaining) + * Set the motor to go *backward* */ - @Override - public Motor setInverted(boolean inv) { - getDevice().setDirection(inv ? DcMotorSimple.Direction.FORWARD : DcMotorSimple.Direction.REVERSE); - invert = inv; + public Motor setBackward() { + getDevice().setDirection(DcMotorSimple.Direction.REVERSE); return this; } /** - * Invert the motor (toggle inversion) - * - * @return The motor (for chaining) + * Set the motor to go *forward* */ - @Override - public Motor invert() { - return setInverted(!getInverted()); + public Motor setForward() { + getDevice().setDirection(DcMotorSimple.Direction.FORWARD); + return this; + } + + /** + * Set the motor to go in a particular direction + */ + public Motor setDirection(DcMotorSimple.Direction dir) { + getDevice().setDirection(dir); + return this; } /** * Gets the power value for the motor * * @return the power value (as a double) + * @deprecated use getPower() instead */ + @Deprecated public double getSpeed() { + return getPower(); + } + + /** + * Gets the power value for the motor + * + * @return the power value (as a double) + */ + public double getPower() { return device.getPower(); } /** - * Set speed of motor + * Set the (range-clipped) speed of motor * * @param speed The speed of the motor */ + @Deprecated public void setSpeed(double speed) { - device.setPower(Range.clip(speed, min, max)); + setPower(speed); + } + + /** + * Set the (range-clipped) power of the motor + * + * @param pow The power value (-1 -> 1) + */ + public void setPower(double pow) { + device.setPower(Range.clip(pow, min, max)); } /** diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/MotorGroup.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/MotorGroup.java index 77744e0d..347739e3 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/MotorGroup.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/motor/MotorGroup.java @@ -3,7 +3,8 @@ import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.technototes.library.hardware.HardwareDeviceGroup; -/** Class for a group of motors +/** + * Class for a group of motors * * @param The type of motors to group */ @@ -12,7 +13,8 @@ public class MotorGroup extends Motor implements Har private final Motor[] followers; - /** Make a motor group + /** + * Make a motor group * * @param motors The motors */ @@ -37,15 +39,18 @@ public Motor[] getAllDevices() { } @Override - public void propogate(double value) { - for (Motor m : followers) { - m.setSpeed(value); + public void setSpeed(double speed) { + super.setSpeed(speed); + propagate(obj -> obj.setSpeed(speed)); + } + + public void setSpeeds(double... speeds) { + for (int i = 0; i < speeds.length && i < getDeviceCount(); i++) { + getDeviceNum(i).setSpeed(speeds[i]); } } - @Override - public void setSpeed(double speed) { - super.setSpeed(speed); - propogate(speed); + public Motor getDeviceNum(int i) { + return (i == 0) ? this : followers[i - 1]; } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/IMU.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/IMU.java index 9d3c330f..4c235c3a 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/IMU.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/IMU.java @@ -15,7 +15,10 @@ public class IMU extends Sensor implements /** * The direction of the axes signs when remapping the axes + * + * Probably don't use this stuff. Just use the IMU direction from the 8.1 and later SDK */ + @Deprecated public enum AxesSigns { /** * Positive, Positive, Positive @@ -74,7 +77,10 @@ public enum AxesSigns { /** * Make an imu + * + * Use the Logo/Usb Facing direction API's as part of the FTC 8.1+ SDK */ + @Deprecated public IMU(com.qualcomm.robotcore.hardware.IMU device, com.qualcomm.robotcore.hardware.IMU.Parameters params) { super(device); angleOffset = 0.0; @@ -88,7 +94,10 @@ public IMU(com.qualcomm.robotcore.hardware.IMU device, com.qualcomm.robotcore.ha /** * Make an imu + * + * Use the Logo/Usb Facing direction API's as part of the FTC 8.1+ SDK */ + @Deprecated public IMU(String deviceName, com.qualcomm.robotcore.hardware.IMU.Parameters params) { super(deviceName); angleOffset = 0.0; @@ -238,6 +247,7 @@ public IMU remapAxesAndSigns(AxesOrder order, AxesSigns signs) { * @param legacySigns The *legacy* signs desired * @return this (for chaining) */ + @Deprecated public IMU remapLegacyAxes(AxesOrder legacyOrder, AxesSigns legacySigns) { // The BNO055 has the X and Y axes rotated 90 degrees :/ // These are *very* untested diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/Rev2MDistanceSensor.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/Rev2MDistanceSensor.java index 942bccf2..343160d2 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/Rev2MDistanceSensor.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/Rev2MDistanceSensor.java @@ -9,7 +9,6 @@ * * @author Alex Stedman */ -@Deprecated @SuppressWarnings("unused") public class Rev2MDistanceSensor extends Sensor implements IDistanceSensor { diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/Sensor.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/Sensor.java index 667f2b4a..423dca7f 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/Sensor.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/Sensor.java @@ -8,7 +8,6 @@ * @param The Sensor hardware device * @author Alex Stedman */ -@Deprecated @SuppressWarnings("unused") public abstract class Sensor extends HardwareDevice { diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/encoder/ExternalEncoder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/encoder/ExternalEncoder.java index d3ce9a95..6f1cd74b 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/encoder/ExternalEncoder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/encoder/ExternalEncoder.java @@ -43,6 +43,10 @@ public void zeroEncoder() { */ @Override public double getSensorValue() { - return getDevice().getVoltage() - zero; + AnalogInput device = getRawDevice(); + if (device != null) { + val = device.getVoltage(); + } + return val - zero; } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/encoder/MotorEncoder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/encoder/MotorEncoder.java index 15eb8f36..140c71a4 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/encoder/MotorEncoder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/sensor/encoder/MotorEncoder.java @@ -75,10 +75,6 @@ public MotorEncoder(DcMotorEx motor) { this(motor, new ElapsedTime()); } - public MotorEncoder(EncodedMotor motor) { - this(motor.getDevice()); - } - public MotorEncoder(String deviceName) { this(hardwareMap.get(DcMotorEx.class, deviceName)); } diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/MotorAsServo.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/MotorAsServo.java new file mode 100644 index 00000000..36db14cb --- /dev/null +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/MotorAsServo.java @@ -0,0 +1,56 @@ +package com.technototes.library.hardware.servo; + +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.technototes.library.hardware.HardwareDevice; +import com.technototes.library.hardware.Sensored; +import java.io.InvalidClassException; + +/** + * This is to use a motor as a servo using the built-in capabilities (instead of doing it manually) + * + * One rather important feature would be to hand control back & forth between a normal encoded + * motor. The alternative would be to extend EncodedMotor to just "do" this stuff automatically. + * Honestly, that probably makes more sense, but requires some thought about state transitions. + * + * @param + * Not Yet Implemented! + * TODO: Implement this + * + */ +public class MotorAsServo extends HardwareDevice implements Sensored { + + public MotorAsServo(T device, String deviceName) throws InvalidClassException { + super(device, deviceName); + throw new InvalidClassException("com.technototes.library.hardware.servo.MotorAsServo", "Not Yet Implemented"); + } + + protected MotorAsServo(String deviceName) throws InvalidClassException { + super(deviceName); + throw new InvalidClassException("com.technototes.library.hardware.servo.MotorAsServo", "Not Yet Implemented"); + } + + /** + * @return + */ + @Override + public String LogLine() { + return null; + } + + /** + * @return + */ + @Override + public double getSensorValue() { + return 0; + } + + /** + * @return + */ + @Override + public double getAsDouble() { + return getSensorValue(); + } +} diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/Servo.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/Servo.java index 701f0192..5420a9f4 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/Servo.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/Servo.java @@ -15,7 +15,6 @@ * * @author Alex Stedman */ -@Deprecated @SuppressWarnings("unused") public class Servo extends HardwareDevice diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/ServoGroup.java b/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/ServoGroup.java index c80ef063..931e7660 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/ServoGroup.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware/servo/ServoGroup.java @@ -8,7 +8,6 @@ * * @author Alex Stedman */ -@Deprecated @SuppressWarnings("unused") public class ServoGroup extends Servo implements HardwareDeviceGroup { @@ -40,16 +39,20 @@ public Servo[] getAllDevices() { } @Override - public void propogate(double value) { - for (Servo s : followers) { - s.setPosition(value); - } + public Servo getDeviceNum(int i) { + return (i == 0) ? this : followers[i - 1]; } @Override public void setPosition(double position) { super.setPosition(position); - propogate(position); + propagate(obj -> obj.setPosition(position)); + } + + public void setPositions(double... positions) { + for (int i = 0; i < positions.length && i < getDeviceCount(); i++) { + getDeviceNum(i).setPosition(positions[i]); + } } @Override diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware2/AnalogBuilder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware2/AnalogBuilder.java index 07e3b6ed..adaa1088 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware2/AnalogBuilder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware2/AnalogBuilder.java @@ -5,7 +5,9 @@ /** * TODO: Remove this. I don't believe this adds much value. Yeah, HardwareMap.get is weird, but * it's in all the documentation, so just read it, see it in the examples, and you're done. + * */ +@Deprecated public class AnalogBuilder extends HardwareBuilder { public AnalogBuilder(String name) { diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware2/CRServoBuilder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware2/CRServoBuilder.java index 87e03c77..b00a1248 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware2/CRServoBuilder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware2/CRServoBuilder.java @@ -7,6 +7,7 @@ * TODO: Remove this. I don't believe this adds much value. Yeah, HardwareMap.get is weird, but * it's in all the documentation, so just read it, see it in the examples, and you're done. */ +@Deprecated public class CRServoBuilder extends HardwareBuilder { public CRServoBuilder(String name) { diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware2/ColorBuilder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware2/ColorBuilder.java index e8c1fc60..52d9264e 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware2/ColorBuilder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware2/ColorBuilder.java @@ -6,6 +6,7 @@ * TODO: Remove this. I don't believe this adds much value. Yeah, HardwareMap.get is weird, but * it's in all the documentation, so just read it, see it in the examples, and you're done. */ +@Deprecated public class ColorBuilder extends HardwareBuilder { public ColorBuilder(String name) { diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware2/ColorRangeBuilder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware2/ColorRangeBuilder.java index 95d26915..8d760997 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware2/ColorRangeBuilder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware2/ColorRangeBuilder.java @@ -6,6 +6,7 @@ * TODO: Remove this. I don't believe this adds much value. Yeah, HardwareMap.get is weird, but * it's in all the documentation, so just read it, see it in the examples, and you're done. */ +@Deprecated public class ColorRangeBuilder extends HardwareBuilder { public ColorRangeBuilder(String name) { diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware2/DigitalBuilder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware2/DigitalBuilder.java index 86fc59aa..1842ffc7 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware2/DigitalBuilder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware2/DigitalBuilder.java @@ -6,6 +6,7 @@ * TODO: Remove this. I don't believe this adds much value. Yeah, HardwareMap.get is weird, but * it's in all the documentation, so just read it, see it in the examples, and you're done. */ +@Deprecated public class DigitalBuilder extends HardwareBuilder { /** diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware2/DistanceBuilder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware2/DistanceBuilder.java index 42aadcc7..094fc57a 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware2/DistanceBuilder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware2/DistanceBuilder.java @@ -6,6 +6,7 @@ * TODO: Remove this. I don't believe this adds much value. Yeah, HardwareMap.get is weird, but * it's in all the documentation, so just read it, see it in the examples, and you're done. */ +@Deprecated public class DistanceBuilder extends HardwareBuilder { public DistanceBuilder(String name) { diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware2/HardwareBuilder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware2/HardwareBuilder.java index 0dd694e8..d0d2d209 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware2/HardwareBuilder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware2/HardwareBuilder.java @@ -7,6 +7,7 @@ * TODO: Remove this. I don't believe this adds much value. Yeah, HardwareMap.get is weird, but * it's in all the documentation, so just read it, see it in the examples, and you're done. */ +@Deprecated public class HardwareBuilder { private static HardwareMap hardwareMap = null; diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware2/IMUBuilder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware2/IMUBuilder.java index 3555d0ee..d3bebe9a 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware2/IMUBuilder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware2/IMUBuilder.java @@ -9,6 +9,7 @@ * TODO: Remove this. I don't believe this adds much value. Yeah, HardwareMap.get is weird, but * it's in all the documentation, so just read it, see it in the examples, and you're done. */ +@Deprecated public class IMUBuilder extends HardwareBuilder { /** diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware2/MotorBuilder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware2/MotorBuilder.java index d5fa7db8..d6dbc61a 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware2/MotorBuilder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware2/MotorBuilder.java @@ -9,6 +9,7 @@ * TODO: Remove this. I don't believe this adds much value. Yeah, HardwareMap.get is weird, but * it's in all the documentation, so just read it, see it in the examples, and you're done. */ +@Deprecated public class MotorBuilder extends HardwareBuilder { public MotorBuilder(String name) { diff --git a/RobotLibrary/src/main/java/com/technototes/library/hardware2/ServoBuilder.java b/RobotLibrary/src/main/java/com/technototes/library/hardware2/ServoBuilder.java index b2119fe0..6589318a 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/hardware2/ServoBuilder.java +++ b/RobotLibrary/src/main/java/com/technototes/library/hardware2/ServoBuilder.java @@ -7,6 +7,7 @@ * TODO: Remove this. I don't believe this adds much value. Yeah, HardwareMap.get is weird, but * it's in all the documentation, so just read it, see it in the examples, and you're done. */ +@Deprecated public class ServoBuilder extends HardwareBuilder { public ServoBuilder(String name) { diff --git a/RobotLibrary/src/main/java/com/technototes/library/logger/Log.java b/RobotLibrary/src/main/java/com/technototes/library/logger/Log.java index fedcf771..d734833d 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/logger/Log.java +++ b/RobotLibrary/src/main/java/com/technototes/library/logger/Log.java @@ -4,7 +4,6 @@ import static java.lang.annotation.ElementType.LOCAL_VARIABLE; import static java.lang.annotation.ElementType.METHOD; -import com.technototes.library.util.Color; import java.lang.annotation.Documented; import java.lang.annotation.ElementType; import java.lang.annotation.Repeatable; @@ -44,18 +43,6 @@ */ String format() default "%s"; - /** The color for the entry - * - * @return The color - */ - Color entryColor() default Color.NO_COLOR; - - /** The color for the tag for the entry - * - * @return The color - */ - Color color() default Color.NO_COLOR; - @Documented @Retention(RetentionPolicy.RUNTIME) @Target({ ElementType.FIELD, ElementType.METHOD }) @@ -86,149 +73,6 @@ * @return The name as a string */ String name() default ""; - - /** The color for the tag for the number - * - * @return The color - */ - Color color() default Color.NO_COLOR; - - /** The color for the number - * - * @return The color - */ - Color numberColor() default Color.NO_COLOR; - } - - /** Log a number, but store it as a number bar - * - */ - @Retention(RetentionPolicy.RUNTIME) - @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) - @interface NumberBar { - /** Store index for this annotation (position in telemetry) - * - * @return The index - */ - int index() default -1; - - /** Store priority for this log entry (to pick the most wanted entry over others with same index) - * - * @return The priority - */ - int priority() default -1; - - /** Store the min for the number bar to scale to - * - * @return The min - */ - double min() default -1; - - /** Store the max for the number bar to scale to - * - * @return The max - */ - double max() default 1; - - /** Store the scale for the number bar to scale to - * - * @return The scale - */ - double scale() default 0.1; - - /** Store the name for this annotation to be be beside - * - * @return The name as a string - */ - String name() default ""; - - /** The color for the tag for the bar - * - * @return The color - */ - Color color() default Color.NO_COLOR; - - /** The color for the filled in bar color - * - * @return The color - */ - Color completeBarColor() default Color.NO_COLOR; - - /** The color for the not filled in bar color - * - * @return The color - */ - Color incompleteBarColor() default Color.NO_COLOR; - - /** The color for the bar outlines - * - * @return The color - */ - Color outline() default Color.NO_COLOR; - } - - @Retention(RetentionPolicy.RUNTIME) - @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) - @interface NumberSlider { - /** Store index for this annotation (position in telemetry) - * - * @return The index - */ - int index() default -1; - - /** Store priority for this log entry (to pick the most wanted entry over others with same index) - * - * @return The priority - */ - int priority() default -1; - - /** Store the min for the number bar to scale to - * - * @return The min - */ - double min() default -1; - - /** Store the max for the number bar to scale to - * - * @return The max - */ - double max() default 1; - - /** Store the scale for the number bar to scale to - * - * @return The scale - */ - double scale() default 0.1; - - /** Store the name for this annotation to be be beside - * - * @return The name as a string - */ - String name() default ""; - - /** The color for the tag for the slider - * - * @return The color - */ - Color color() default Color.NO_COLOR; - - /** The color for the slider background - * - * @return The color - */ - Color sliderBackground() default Color.NO_COLOR; - - /** The color for the slider outline - * - * @return The color - */ - Color outline() default Color.NO_COLOR; - - /** The color for the slider slide - * - * @return The color - */ - Color slider() default Color.NO_COLOR; } @Retention(RetentionPolicy.RUNTIME) @@ -252,46 +96,16 @@ */ String trueValue() default "true"; - /** The format for when the boolean returns true - * - * @return The String format - */ - String trueFormat() default "%s"; - - /** The color for the true String - * - * @return The color - */ - Color trueColor() default Color.NO_COLOR; - /** Store the string when the annotated method returns false * * @return The string */ String falseValue() default "false"; - /** The format for when the boolean returns false - * - * @return The String format - */ - String falseFormat() default "%s"; - - /** The color for the false String - * - * @return The color - */ - Color falseColor() default Color.NO_COLOR; - /** Store the name for this annotation to be be beside * * @return The name as a string */ String name() default ""; - - /** The color for the tag for the boolean - * - * @return The color - */ - Color color() default Color.NO_COLOR; } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/logger/LogConfig.java b/RobotLibrary/src/main/java/com/technototes/library/logger/LogConfig.java index 3288579e..e3f4919d 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/logger/LogConfig.java +++ b/RobotLibrary/src/main/java/com/technototes/library/logger/LogConfig.java @@ -32,26 +32,26 @@ boolean duringInit() default false; } - /** Annotation for Whitelisting Opmodes to log this item + /** Annotation for allowing Opmodes to log this item * */ @Retention(RetentionPolicy.RUNTIME) @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) - @interface Whitelist { - /** The whitelisted opmodes + @interface AllowList { + /** The allowed opmodes * * @return Opmode Classes */ Class[] value(); } - /** Annotation for Blacklisting Opmodes to log this item + /** Annotation for denying Opmodes to log this item * */ @Retention(RetentionPolicy.RUNTIME) @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) - @interface Blacklist { - /** The blacklisted opmodes + @interface DenyList { + /** The denied opmodes * * @return Opmode Classes */ diff --git a/RobotLibrary/src/main/java/com/technototes/library/logger/Logger.java b/RobotLibrary/src/main/java/com/technototes/library/logger/Logger.java index bbe5831e..bbb2ddfc 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/logger/Logger.java +++ b/RobotLibrary/src/main/java/com/technototes/library/logger/Logger.java @@ -3,15 +3,12 @@ import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.technototes.library.logger.entry.BooleanEntry; import com.technototes.library.logger.entry.Entry; -import com.technototes.library.logger.entry.NumberBarEntry; import com.technototes.library.logger.entry.NumberEntry; -import com.technototes.library.logger.entry.NumberSliderEntry; import com.technototes.library.logger.entry.StringEntry; import java.lang.annotation.Annotation; import java.lang.reflect.Field; import java.lang.reflect.InvocationTargetException; import java.lang.reflect.Method; -import java.sql.Array; import java.util.ArrayList; import java.util.Arrays; import java.util.LinkedHashSet; @@ -34,6 +31,7 @@ public class Logger { public Entry[] initEntries; private final Set> unindexedRunEntries; private final Set> unindexedInitEntries; + private final Set recordedAlready; private final Telemetry telemetry; private final OpMode opMode; /** @@ -52,6 +50,7 @@ public Logger(OpMode op) { telemetry.setDisplayFormat(Telemetry.DisplayFormat.HTML); unindexedRunEntries = new LinkedHashSet<>(); unindexedInitEntries = new LinkedHashSet<>(); + recordedAlready = new LinkedHashSet<>(); configure(op); runEntries = generate(unindexedRunEntries); initEntries = generate(unindexedInitEntries); @@ -61,14 +60,13 @@ private void configure(Object root) { for (Field field : root.getClass().getFields()) { try { Object o = field.get(root); - if (isFieldAllowed(field)) { + if (!recordedAlready.contains(o) && isFieldAllowed(field)) { if (o instanceof Loggable) { configure(o); + recordedAlready.add(o); } else if ( field.isAnnotationPresent(Log.class) || field.isAnnotationPresent(Log.Number.class) || - field.isAnnotationPresent(Log.NumberSlider.class) || - field.isAnnotationPresent(Log.NumberBar.class) || field.isAnnotationPresent(Log.Boolean.class) ) { if (field.getType().isPrimitive() || o instanceof String) { @@ -126,11 +124,13 @@ private Entry[] generate(Set> a) { private void update(Entry[] choice) { try { - for (int i = 0; i < choice.length; i++) { - telemetry.addLine( - (i > 9 ? i + "| " : i + " | ") + - (choice[i] == null ? "" : choice[i].getTag().replace('`', captionDivider) + choice[i].toString()) - ); + for (Entry item : choice) { + // telemetry.addLine( + // (i > 9 ? i + "| " : i + " | ") + + // (choice[i] == null ? "" : choice[i].getTag().replace('`', captionDivider) + choice[i].toString()) + // ); + // All teh fancy HTML stuff gets in the way of the FTC Dashboard graph + telemetry.addData(item.getName(), item.get()); } telemetry.update(); } catch (Exception ignored) {} @@ -183,56 +183,11 @@ private void set(Annotation[] a, Supplier m) { boolean init = false, run = true; Entry e = null; for (Annotation as : a) { - if (as instanceof Log.NumberSlider) { - e = - new NumberSliderEntry( - ((Log.NumberSlider) as).name(), - (Supplier) m, - ((Log.NumberSlider) as).index(), - ((Log.NumberSlider) as).min(), - ((Log.NumberSlider) as).max(), - ((Log.NumberSlider) as).scale(), - ((Log.NumberSlider) as).color(), - ((Log.NumberSlider) as).sliderBackground(), - ((Log.NumberSlider) as).outline(), - ((Log.NumberSlider) as).slider() - ); - e.setPriority(((Log.NumberSlider) as).priority()); - } else if (as instanceof Log.NumberBar) { - e = - new NumberBarEntry( - ((Log.NumberBar) as).name(), - (Supplier) m, - ((Log.NumberBar) as).index(), - ((Log.NumberBar) as).min(), - ((Log.NumberBar) as).max(), - ((Log.NumberBar) as).scale(), - ((Log.NumberBar) as).color(), - ((Log.NumberBar) as).completeBarColor(), - ((Log.NumberBar) as).outline(), - ((Log.NumberBar) as).incompleteBarColor() - ); - e.setPriority(((Log.NumberBar) as).priority()); - } else if (as instanceof Log.Number) { - e = - new NumberEntry( - ((Log.Number) as).name(), - (Supplier) m, - ((Log.Number) as).index(), - ((Log.Number) as).color(), - ((Log.Number) as).numberColor() - ); + if (as instanceof Log.Number) { + e = new NumberEntry(((Log.Number) as).name(), (Supplier) m, ((Log.Number) as).index()); e.setPriority(((Log.Number) as).priority()); } else if (as instanceof Log) { - e = - new StringEntry( - ((Log) as).name(), - (Supplier) m, - ((Log) as).index(), - ((Log) as).color(), - ((Log) as).format(), - ((Log) as).entryColor() - ); + e = new StringEntry(((Log) as).name(), (Supplier) m, ((Log) as).index(), ((Log) as).format()); e.setPriority(((Log) as).priority()); } else if (as instanceof Log.Boolean) { e = @@ -241,12 +196,7 @@ private void set(Annotation[] a, Supplier m) { (Supplier) m, ((Log.Boolean) as).index(), ((Log.Boolean) as).trueValue(), - ((Log.Boolean) as).falseValue(), - ((Log.Boolean) as).color(), - ((Log.Boolean) as).trueFormat(), - ((Log.Boolean) as).falseFormat(), - ((Log.Boolean) as).trueColor(), - ((Log.Boolean) as).falseColor() + ((Log.Boolean) as).falseValue() ); e.setPriority(((Log.Boolean) as).priority()); } else if (as instanceof LogConfig.Run) { @@ -300,13 +250,13 @@ private static Supplier getCustom(Object o) { } private boolean isFieldAllowed(Field f) { - if (f.isAnnotationPresent(LogConfig.Whitelist.class)) { - if (!Arrays.asList(f.getAnnotation(LogConfig.Whitelist.class).value()).contains(opMode.getClass())) { + if (f.isAnnotationPresent(LogConfig.AllowList.class)) { + if (!Arrays.asList(f.getAnnotation(LogConfig.AllowList.class).value()).contains(opMode.getClass())) { return false; } } - if (f.isAnnotationPresent(LogConfig.Blacklist.class)) { - if (Arrays.asList(f.getAnnotation(LogConfig.Blacklist.class).value()).contains(opMode.getClass())) { + if (f.isAnnotationPresent(LogConfig.DenyList.class)) { + if (Arrays.asList(f.getAnnotation(LogConfig.DenyList.class).value()).contains(opMode.getClass())) { return false; } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/BooleanEntry.java b/RobotLibrary/src/main/java/com/technototes/library/logger/entry/BooleanEntry.java index 21d201ed..4a221789 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/BooleanEntry.java +++ b/RobotLibrary/src/main/java/com/technototes/library/logger/entry/BooleanEntry.java @@ -5,27 +5,16 @@ public class BooleanEntry extends Entry { - private StringEntry trueEntry, falseEntry; + private String trueEntry, falseEntry; - public BooleanEntry( - String n, - Supplier s, - int index, - String wt, - String wf, - Color c, - String tf, - String ff, - Color tc, - Color fc - ) { - super(n, s, index, c); - trueEntry = new StringEntry("", () -> wt, -1, Color.NO_COLOR, tf, tc); - falseEntry = new StringEntry("", () -> wf, -1, Color.NO_COLOR, ff, fc); + public BooleanEntry(String n, Supplier s, int index, String wt, String wf) { + super(n, s, index); + trueEntry = wt; + falseEntry = wf; } @Override public String toString() { - return (get() ? trueEntry : falseEntry).get(); + return (get() ? trueEntry : falseEntry); } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/Entry.java b/RobotLibrary/src/main/java/com/technototes/library/logger/entry/Entry.java index a4adf087..aa788e02 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/Entry.java +++ b/RobotLibrary/src/main/java/com/technototes/library/logger/entry/Entry.java @@ -1,6 +1,5 @@ package com.technototes.library.logger.entry; -import com.technototes.library.util.Color; import java.util.function.Supplier; /** @@ -27,29 +26,18 @@ public abstract class Entry implements Supplier { * The name of the Entry */ protected String name; - /** - * String to use a 'header' (calculated from name and color) - */ - protected String tag; - /** - * Color to display - */ - protected Color color; /** - * Create an entry with name, value, index, and color + * Create an entry with name, value, index * * @param n Name of the entry * @param s Value function to display * @param index Index of the entry - * @param c Color to display */ - public Entry(String n, Supplier s, int index, Color c) { + public Entry(String n, Supplier s, int index) { x = index; supplier = s; name = n; - color = c; - tag = (name.equals("") ? " " : color.format(name) + " ` "); } /** @@ -79,16 +67,7 @@ public String toString() { } /** - * The tag for the entry - * - * @return The tag - */ - public String getTag() { - return tag; - } - - /** - * Get the name (unformatted tag) + * Get the name * * @return The name */ diff --git a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/NumberBarEntry.java b/RobotLibrary/src/main/java/com/technototes/library/logger/entry/NumberBarEntry.java deleted file mode 100644 index f2ec744f..00000000 --- a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/NumberBarEntry.java +++ /dev/null @@ -1,35 +0,0 @@ -package com.technototes.library.logger.entry; - -import com.technototes.library.logger.Logger; -import com.technototes.library.util.Color; -import java.util.function.Supplier; - -public class NumberBarEntry extends NumberSliderEntry { - - // primary is bar color, secondary is outline, tertiary is incomplete bar - public NumberBarEntry( - String n, - Supplier s, - int x, - Number mi, - Number ma, - Number sc, - Color c, - Color pri, - Color sec, - Color tert - ) { - super(n, s, x, mi, ma, sc, c, pri, sec, tert); - } - - @Override - public String toString() { - StringBuilder r = new StringBuilder(secondary.format("[")); - int totalAmt = (int) ((max() - min()) / scale()); - int fullAmt = (int) (Math.round((getDouble() - min()) / scale())); - r.append(primary.format(Logger.repeat("█", fullAmt + 1))); - r.append(tertiary.format(Logger.repeat("━", totalAmt - fullAmt))); - r.append(secondary.format("]")); - return r.toString(); - } -} diff --git a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/NumberEntry.java b/RobotLibrary/src/main/java/com/technototes/library/logger/entry/NumberEntry.java index fa024288..b08f1f1f 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/NumberEntry.java +++ b/RobotLibrary/src/main/java/com/technototes/library/logger/entry/NumberEntry.java @@ -7,14 +7,8 @@ public class NumberEntry extends Entry { protected Color numberColor; - public NumberEntry(String n, Supplier s, int x, Color c, Color num) { - super(n, s, x, c); - numberColor = num; - } - - public NumberEntry(String n, Supplier s, int x, Color c) { - super(n, s, x, c); - numberColor = Color.NO_COLOR; + public NumberEntry(String n, Supplier s, int x) { + super(n, s, x); } @Override diff --git a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/NumberSliderEntry.java b/RobotLibrary/src/main/java/com/technototes/library/logger/entry/NumberSliderEntry.java deleted file mode 100644 index 59f212ed..00000000 --- a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/NumberSliderEntry.java +++ /dev/null @@ -1,60 +0,0 @@ -package com.technototes.library.logger.entry; - -import com.technototes.library.logger.Logger; -import com.technototes.library.util.Color; -import java.util.function.Supplier; - -public class NumberSliderEntry extends NumberEntry { - - protected Number min, max, scale; - protected Color primary, secondary, tertiary; - - public NumberSliderEntry( - String n, - Supplier s, - int x, - Number mi, - Number ma, - Number sc, - Color c, - Color pr, - Color sec, - Color tert - ) { - super(n, s, x, c); - min = mi; - max = ma; - scale = sc; - primary = pr; - secondary = sec; - tertiary = tert; - } - - public double min() { - return min.doubleValue(); - } - - public double max() { - return max.doubleValue(); - } - - public double scale() { - return scale.doubleValue(); - } - - public double getDouble() { - return get().doubleValue(); - } - - @Override - public String toString() { - StringBuilder r = new StringBuilder(secondary.format("[")); - int totalAmt = (int) ((max() - min()) / scale()); - int fullAmt = (int) (Math.round((getDouble() - min()) / scale())); - r.append(tertiary.format(Logger.repeat("━", fullAmt))); - r.append(primary.format("█")); - r.append(tertiary.format(Logger.repeat("━", totalAmt - fullAmt))); - r.append(secondary.format("]")); - return r.toString(); - } -} diff --git a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/StringEntry.java b/RobotLibrary/src/main/java/com/technototes/library/logger/entry/StringEntry.java index 0f515650..1c1bc536 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/logger/entry/StringEntry.java +++ b/RobotLibrary/src/main/java/com/technototes/library/logger/entry/StringEntry.java @@ -1,21 +1,18 @@ package com.technototes.library.logger.entry; -import com.technototes.library.util.Color; import java.util.function.Supplier; public class StringEntry extends Entry { private String format; - private Color entryColor; - public StringEntry(String n, Supplier s, int x, Color c, String f, Color ec) { - super(n, s, x, c); + public StringEntry(String n, Supplier s, int x, String f) { + super(n, s, x); format = f; - entryColor = ec; } @Override public String toString() { - return entryColor.format(format, get()); + return String.format(format, get()); } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/structure/CommandOpMode.java b/RobotLibrary/src/main/java/com/technototes/library/structure/CommandOpMode.java index 81419465..c8dd453f 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/structure/CommandOpMode.java +++ b/RobotLibrary/src/main/java/com/technototes/library/structure/CommandOpMode.java @@ -61,7 +61,8 @@ public double getOpModeRuntime() { @Override public final void runOpMode() { opModeState = OpModeState.INIT; - CommandScheduler.resetScheduler().setOpMode(this); + CommandScheduler.resetScheduler(); + CommandScheduler.setOpMode(this); hubs = hardwareMap.getAll(LynxModule.class); hubs.forEach(e -> e.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL)); HardwareBuilder.initMap(hardwareMap); @@ -73,20 +74,20 @@ public final void runOpMode() { while (!(isStarted() && additionalInitConditions()) && !terminated && !isStopRequested()) { initLoop(); universalLoop(); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); logger.initUpdate(); driverGamepad.periodic(); codriverGamepad.periodic(); hubs.forEach(LynxModule::clearBulkCache); } opModeState = OpModeState.RUN; - CommandScheduler.getInstance().run(); + CommandScheduler.run(); uponStart(); opModeTimer.reset(); while (opModeIsActive() && !terminated && !isStopRequested()) { runLoop(); universalLoop(); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); logger.runUpdate(); driverGamepad.periodic(); codriverGamepad.periodic(); @@ -94,7 +95,7 @@ public final void runOpMode() { } opModeState = OpModeState.END; end(); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); CommandScheduler.resetScheduler(); opModeTimer.reset(); } diff --git a/RobotLibrary/src/main/java/com/technototes/library/subsystem/DeviceSubsystem.java b/RobotLibrary/src/main/java/com/technototes/library/subsystem/DeviceSubsystem.java index 51ffdf88..f48abf52 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/subsystem/DeviceSubsystem.java +++ b/RobotLibrary/src/main/java/com/technototes/library/subsystem/DeviceSubsystem.java @@ -2,10 +2,13 @@ import com.technototes.library.hardware.HardwareDevice; -/** class for subsystems +/** + * Don't do this, don't use this. Subsystems should be used for encapsulation, not for exposing + * the rest of the system to a hardware device * @author Alex Stedman * @param The {@link HardwareDevice} for this subsystem */ +@Deprecated public abstract class DeviceSubsystem> implements Subsystem { protected T device; diff --git a/RobotLibrary/src/main/java/com/technototes/library/subsystem/Subsystem.java b/RobotLibrary/src/main/java/com/technototes/library/subsystem/Subsystem.java index 5661c3ff..bc7a21b8 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/subsystem/Subsystem.java +++ b/RobotLibrary/src/main/java/com/technototes/library/subsystem/Subsystem.java @@ -6,16 +6,16 @@ public interface Subsystem extends Periodic { default void register() { - CommandScheduler.getInstance().register(this); + CommandScheduler.register(this); } default Subsystem setDefaultCommand(Command c) { - CommandScheduler.getInstance().scheduleDefault(c, this); + CommandScheduler.scheduleDefault(c, this); return this; } default Command getDefaultCommand() { - return CommandScheduler.getInstance().getDefault(this); + return CommandScheduler.getDefault(this); } @Override diff --git a/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/DrivebaseSubsystem.java b/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/DrivebaseSubsystem.java index 4e43fd42..5d377a10 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/DrivebaseSubsystem.java +++ b/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/DrivebaseSubsystem.java @@ -3,7 +3,7 @@ import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.technototes.library.hardware.motor.Motor; import com.technototes.library.hardware.motor.MotorGroup; -import com.technototes.library.subsystem.DeviceSubsystem; +import com.technototes.library.subsystem.Subsystem; import java.util.function.DoubleSupplier; /** @@ -12,7 +12,9 @@ * @param The type of motors for the drivebase * @author Alex Stedman The motors for the drivebase */ -public abstract class DrivebaseSubsystem extends DeviceSubsystem> { +public abstract class DrivebaseSubsystem implements Subsystem { + + protected MotorGroup motors; /** * Override this to get the gyroscope heading. @@ -26,7 +28,7 @@ public abstract class DrivebaseSubsystem extends Device * @param motors The drive motors */ public DrivebaseSubsystem(Motor... motors) { - super(new MotorGroup(motors)); + this.motors = new MotorGroup(motors); } /** @@ -36,7 +38,7 @@ public DrivebaseSubsystem(Motor... motors) { * @param motors The drive motors */ public DrivebaseSubsystem(DoubleSupplier gyro, Motor... motors) { - super(new MotorGroup(motors)); + this.motors = new MotorGroup(motors); gyroSupplier = gyro; } diff --git a/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/SimpleMecanumDrivebaseSubsystem.java b/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/SimpleMecanumDrivebaseSubsystem.java index 3ec21f5b..fea4021d 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/SimpleMecanumDrivebaseSubsystem.java +++ b/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/SimpleMecanumDrivebaseSubsystem.java @@ -5,18 +5,35 @@ import com.technototes.library.hardware.motor.Motor; import java.util.function.DoubleSupplier; -/** Class for mecanum/xdrive drivebases - * @author Alex Stedman +/** + * Class for mecanum/xdrive drivebases + * * @param The motor type for the subsystem + * @author Alex Stedman */ public class SimpleMecanumDrivebaseSubsystem extends DrivebaseSubsystem { - /** Drive motors - * + /** + * Drive motors */ - public Motor flMotor, frMotor, rlMotor, rrMotor; + protected Motor flMotor() { + return motors.getDeviceNum(0); + } + + protected Motor frMotor() { + return motors.getDeviceNum(1); + } + + protected Motor rlMotor() { + return motors.getDeviceNum(2); + } + + protected Motor rrMotor() { + return motors.getDeviceNum(3); + } - /** Create mecanum drivebase + /** + * Create mecanum drivebase * * @param flMotor The front left motor for the drivebase * @param frMotor The front right motor for the drivebase @@ -25,15 +42,12 @@ public class SimpleMecanumDrivebaseSubsystem extends Dr */ public SimpleMecanumDrivebaseSubsystem(Motor flMotor, Motor frMotor, Motor rlMotor, Motor rrMotor) { super(flMotor, frMotor, rlMotor, rrMotor); - this.flMotor = flMotor; - this.frMotor = frMotor; - this.rlMotor = rlMotor; - this.rrMotor = rrMotor; } - /** Create mecanum drivebase + /** + * Create mecanum drivebase * - * @param gyro The gyro supplier + * @param gyro The gyro supplier * @param flMotor The front left motor for the drivebase * @param frMotor The front right motor for the drivebase * @param rlMotor The rear left motor for the drivebase @@ -47,10 +61,6 @@ public SimpleMecanumDrivebaseSubsystem( Motor rrMotor ) { super(gyro, flMotor, frMotor, rlMotor, rrMotor); - this.flMotor = flMotor; - this.frMotor = frMotor; - this.rlMotor = rlMotor; - this.rrMotor = rrMotor; } public void joystickDrive(double x, double y, double rotation) { @@ -89,9 +99,6 @@ public void stop() { } public void drive(double flSpeed, double frSpeed, double rlSpeed, double rrSpeed) { - flMotor.setSpeed(flSpeed * getSpeed()); - frMotor.setSpeed(frSpeed * getSpeed()); - rlMotor.setSpeed(rlSpeed * getSpeed()); - rrMotor.setSpeed(rrSpeed * getSpeed()); + motors.setSpeeds(flSpeed * getSpeed(), frSpeed * getSpeed(), rlSpeed * getSpeed(), rrSpeed * getSpeed()); } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/TankDrivebaseSubsystem.java b/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/TankDrivebaseSubsystem.java index 69b7eafb..75a6f670 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/TankDrivebaseSubsystem.java +++ b/RobotLibrary/src/main/java/com/technototes/library/subsystem/drivebase/TankDrivebaseSubsystem.java @@ -4,26 +4,33 @@ import com.qualcomm.robotcore.util.Range; import com.technototes.library.hardware.motor.Motor; -/** Class for drivebase subsystems - * @author Alex Stedman +/** + * Class for drivebase subsystems + * * @param The type of motor for the drivebase + * @author Alex Stedman */ public class TankDrivebaseSubsystem extends DrivebaseSubsystem { - /** Drive motors - * + /** + * Drive motors */ - public Motor leftSide, rightSide; + protected Motor leftSide() { + return motors.getDeviceNum(0); + } + + protected Motor rightSide() { + return motors.getDeviceNum(1); + } - /** Create tank drivebase + /** + * Create tank drivebase * - * @param leftMotor The motor/motorgroup for the left side of the drivebase + * @param leftMotor The motor/motorgroup for the left side of the drivebase * @param rightMotor The motor/motorgroup for the right side of the drivebase */ public TankDrivebaseSubsystem(Motor leftMotor, Motor rightMotor) { super(leftMotor, rightMotor); - leftSide = leftMotor; - rightSide = rightMotor; } public void arcadeDrive(double y, double x) { @@ -40,7 +47,6 @@ public void stop() { } public void drive(double l, double r) { - leftSide.setSpeed(l * getSpeed()); - rightSide.setSpeed(r * getSpeed()); + motors.setSpeeds(l * getSpeed(), r * getSpeed()); } } diff --git a/RobotLibrary/src/main/java/com/technototes/library/subsystem/motor/EncodedMotorSubsystem.java b/RobotLibrary/src/main/java/com/technototes/library/subsystem/motor/EncodedMotorSubsystem.java index 79664970..e9b15f79 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/subsystem/motor/EncodedMotorSubsystem.java +++ b/RobotLibrary/src/main/java/com/technototes/library/subsystem/motor/EncodedMotorSubsystem.java @@ -2,9 +2,14 @@ import com.technototes.library.hardware.motor.EncodedMotor; -/** Class for encoded motor subsystems +/** + * A bad example class for encoded motor subsystems + * + * This is an anti-pattern. + * Subsystems are levels of abstraction. This doesn't provide a real level of abstraction. * @author Alex Stedman */ +@Deprecated public class EncodedMotorSubsystem extends MotorSubsystem> { /** Max speed diff --git a/RobotLibrary/src/main/java/com/technototes/library/subsystem/motor/MotorSubsystem.java b/RobotLibrary/src/main/java/com/technototes/library/subsystem/motor/MotorSubsystem.java index 19d61407..b2b47c06 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/subsystem/motor/MotorSubsystem.java +++ b/RobotLibrary/src/main/java/com/technototes/library/subsystem/motor/MotorSubsystem.java @@ -3,10 +3,15 @@ import com.technototes.library.hardware.motor.Motor; import com.technototes.library.subsystem.DeviceSubsystem; -/** Class for motor subsystems +/** + * a bad example class for motor subsystems: + * Don't expose a device as a subsystem. Subsystems should control/mediate access to the devices, + * not just expose a device. + * * @author Alex Stedman * @param The motor type */ +@Deprecated public class MotorSubsystem> extends DeviceSubsystem { /** Create motor subsystem diff --git a/RobotLibrary/src/main/java/com/technototes/library/subsystem/servo/ServoSubsystem.java b/RobotLibrary/src/main/java/com/technototes/library/subsystem/servo/ServoSubsystem.java index 9cbea8f4..b460c606 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/subsystem/servo/ServoSubsystem.java +++ b/RobotLibrary/src/main/java/com/technototes/library/subsystem/servo/ServoSubsystem.java @@ -4,9 +4,14 @@ import com.technototes.library.hardware.servo.ServoGroup; import com.technototes.library.subsystem.DeviceSubsystem; -/** Class for servo subsystems +/** + * a bad example class for servo subsystems + * + * This is an anti-pattern: Don't expose a servo as a subsystem. Expose capabilities of the + * subsystem, for use by commands * @author Alex Stedman */ +@Deprecated public class ServoSubsystem extends DeviceSubsystem { /** Create servo subsystem diff --git a/RobotLibrary/src/main/java/com/technototes/library/util/Range.java b/RobotLibrary/src/main/java/com/technototes/library/util/Range.java index 5415d52f..7b1cfdac 100644 --- a/RobotLibrary/src/main/java/com/technototes/library/util/Range.java +++ b/RobotLibrary/src/main/java/com/technototes/library/util/Range.java @@ -57,7 +57,7 @@ public void scale(double scalar) { /** * Get the 'middle' of the range * - * @return the average of min & max + * @return the average of min & max */ public double middle() { return (min + max) / 2; diff --git a/RobotLibrary/src/test/java/com/technototes/library/command/CancelCommandTest.java b/RobotLibrary/src/test/java/com/technototes/library/command/CancelCommandTest.java index 4c4ec725..a47ac886 100644 --- a/RobotLibrary/src/test/java/com/technototes/library/command/CancelCommandTest.java +++ b/RobotLibrary/src/test/java/com/technototes/library/command/CancelCommandTest.java @@ -29,9 +29,9 @@ public void scheduleCommand() { Command c = new cmd(); ElapsedTime t = new ElapsedTime(); t.reset(); - CommandScheduler.getInstance().scheduleOnce(c.cancelUpon(() -> c.getRuntime().seconds() > 1)); + CommandScheduler.scheduleOnce(c.cancelUpon(() -> c.getRuntime().seconds() > 1)); while (t.seconds() < 5.5) { - CommandScheduler.getInstance().run(); + CommandScheduler.run(); if (c.justFinished()) System.out.println("finish"); // System.out.println(e++); } diff --git a/RobotLibrary/src/test/java/com/technototes/library/command/CommandGroupTest.java b/RobotLibrary/src/test/java/com/technototes/library/command/CommandGroupTest.java index bf25f7a0..08bada05 100644 --- a/RobotLibrary/src/test/java/com/technototes/library/command/CommandGroupTest.java +++ b/RobotLibrary/src/test/java/com/technototes/library/command/CommandGroupTest.java @@ -15,9 +15,9 @@ public void setup() { @Test public void scheduleCommand() { CommandGroup g = new SequentialCommandGroup(c1, c2, c3, c4, c5); - CommandScheduler.getInstance().schedule(g); + CommandScheduler.schedule(g); for (int i = 0; i < 100; i++) { - CommandScheduler.getInstance().run(); + CommandScheduler.run(); // System.out.println(e++);' } } diff --git a/RobotLibrary/src/test/java/com/technototes/library/command/CommandTest.java b/RobotLibrary/src/test/java/com/technototes/library/command/CommandTest.java index c7a60c51..45a1dbce 100644 --- a/RobotLibrary/src/test/java/com/technototes/library/command/CommandTest.java +++ b/RobotLibrary/src/test/java/com/technototes/library/command/CommandTest.java @@ -20,9 +20,9 @@ public void setup() { public void scheduleCommand() { long i = System.currentTimeMillis(); int e = 0; - CommandScheduler.getInstance().schedule(c.sleep(1)); + CommandScheduler.schedule(c.sleep(1)); while (System.currentTimeMillis() - i < 10500) { - CommandScheduler.getInstance().run(); + CommandScheduler.run(); if (c.justFinished()) System.out.println("finish"); // System.out.println(e++); } diff --git a/RobotLibrary/src/test/java/com/technototes/library/command/RequirementCommandTest.java b/RobotLibrary/src/test/java/com/technototes/library/command/RequirementCommandTest.java index 9fec1e2d..1e4ad95a 100644 --- a/RobotLibrary/src/test/java/com/technototes/library/command/RequirementCommandTest.java +++ b/RobotLibrary/src/test/java/com/technototes/library/command/RequirementCommandTest.java @@ -36,12 +36,12 @@ public void setup() { @Test public void run() { int[] i = new int[1]; - CommandScheduler.getInstance().schedule(command1, () -> i[0] == 0); - CommandScheduler.getInstance().schedule(command2, () -> i[0] == 1); - CommandScheduler.getInstance().schedule(command3, () -> i[0] == 2); + CommandScheduler.schedule(command1, () -> i[0] == 0); + CommandScheduler.schedule(command2, () -> i[0] == 1); + CommandScheduler.schedule(command3, () -> i[0] == 2); for (i[0] = 0; i[0] < 100; i[0]++) { - CommandScheduler.getInstance().run(); + CommandScheduler.run(); System.out.println(" - " + command1.getState() + " - " + command2.getState() + " - " + command3.getState()); } } diff --git a/RobotLibrary/src/test/java/com/technototes/library/command/SimpleCommandTest.java b/RobotLibrary/src/test/java/com/technototes/library/command/SimpleCommandTest.java index 2058e9bc..6ab2ef29 100644 --- a/RobotLibrary/src/test/java/com/technototes/library/command/SimpleCommandTest.java +++ b/RobotLibrary/src/test/java/com/technototes/library/command/SimpleCommandTest.java @@ -43,13 +43,13 @@ public void scheduleCommandNoCancel() { InstantCommand command = new InstantCommand(); // Creating a command shouldn't cause it to be scheduled - CommandScheduler.getInstance().run(); + CommandScheduler.run(); assertEquals(0, command.initialized); assertEquals(0, command.executed); assertEquals(0, command.ended); assertEquals(0, command.canceled); - CommandScheduler.getInstance().schedule(command); + CommandScheduler.schedule(command); // Scheduling a command won't cause it to run until after run() assertEquals(0, command.initialized); @@ -57,7 +57,7 @@ public void scheduleCommandNoCancel() { assertEquals(0, command.ended); assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); // ?? The first run after scheduling a command doesn't do anything for the command // Yes because the first one puts the command into the state of intialization, @@ -68,7 +68,7 @@ public void scheduleCommandNoCancel() { assertEquals(0, command.ended); assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); /* KBF: This is a little odd. For reasons that are obvious in the code, the initialized state exists only before first execution, but not between command @@ -83,7 +83,7 @@ public void scheduleCommandNoCancel() { // assertEquals(0, command.ended); // assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); // The third run after scheduling a command finally runs it assertEquals(1, command.initialized); @@ -91,7 +91,7 @@ public void scheduleCommandNoCancel() { assertEquals(0, command.ended); assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); // The fourth run after scheduling a 'one-shot' command finally ends it assertEquals(1, command.initialized); @@ -99,14 +99,14 @@ public void scheduleCommandNoCancel() { assertEquals(1, command.ended); assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); // An ended command doesn't get scheduled anymore assertEquals(1, command.initialized); assertEquals(1, command.executed); assertEquals(1, command.ended); assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); // An ended command doesn't get scheduled anymore // ?? But it does get initialized // when you schedule a command, its added to a loop. @@ -121,7 +121,7 @@ public void scheduleCommandNoCancel() { // assertEquals(1, command.ended); // assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); // An ended command doesn't get scheduled anymore // ?? But it does get initialized // ?? And executed?? @@ -130,7 +130,7 @@ public void scheduleCommandNoCancel() { assertEquals(1, command.ended); assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); // An ended command doesn't get scheduled anymore // ?? But it does get initialized // ?? And executed?? @@ -140,13 +140,13 @@ public void scheduleCommandNoCancel() { assertEquals(2, command.ended); assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); assertEquals(2, command.initialized); assertEquals(2, command.executed); assertEquals(2, command.ended); assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); // KBF: Commented out, see comment above // assertEquals(3, command.initialized); @@ -154,13 +154,13 @@ public void scheduleCommandNoCancel() { // assertEquals(2, command.ended); // assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); assertEquals(3, command.initialized); assertEquals(3, command.executed); assertEquals(2, command.ended); assertEquals(0, command.canceled); - CommandScheduler.getInstance().run(); + CommandScheduler.run(); assertEquals(3, command.initialized); assertEquals(3, command.executed); assertEquals(3, command.ended); diff --git a/Vision/src/main/java/com/technototes/vision/HSVRange.java b/Vision/src/main/java/com/technototes/vision/HSVRange.java new file mode 100644 index 00000000..65ec0a63 --- /dev/null +++ b/Vision/src/main/java/com/technototes/vision/HSVRange.java @@ -0,0 +1,94 @@ +package com.technototes.vision; + +import org.opencv.core.Scalar; + +/** + * This is used to detect colors in a particular HSV 'range' + */ +/** + * This is used to detect colors in a particular HSV 'range' + */ +public class HSVRange { + + int hueLow, hueHigh; + int satLow, satHigh; + int valLow, valHigh; + + // Private constructor for wrap around/truncation stuff + private HSVRange(int hLo, int hHi, HSVRange copyFrom) { + hueLow = hLo; + hueHigh = hHi; + satLow = copyFrom.satLow; + satHigh = copyFrom.satHigh; + valLow = copyFrom.valLow; + valHigh = copyFrom.valHigh; + } + + /** + * Create an HSV color range, around 'hue' (0-180, 2 degrees) + * + * @param hue The hue (0-179): each unit is *2* degrees! + * @param hRange The +/- on the hue for detection + * @param sLo The low saturation range + * @param sHi The high saturation range + * @param vLo The low value range + * @param vHi The high value range + */ + public HSVRange(int hue, int hRange, int sLo, int sHi, int vLo, int vHi) { + while (hue > 180) { + hue -= 180; + } + while (hue < 0) { + hue += 180; + } + hueLow = hue - Math.min(Math.abs(hRange), 89); + hueHigh = hue + Math.min(Math.abs(hRange), 89); + satLow = Math.min(sLo, sHi); + satHigh = Math.max(sLo, sHi); + valLow = Math.min(vLo, vHi); + valHigh = Math.max(vLo, vHi); + } + + /** + * @return An HSVRange for the 'low end' of the hue range, if it's below 0, null otherwise + */ + public HSVRange makeWrapAround() { + if (hueLow >= 0) { + return null; + } + return new HSVRange(180 + hueLow, 180, this); + } + + /** + * @return An HSVRange for the positive part of a hue range if it spans across 0, null otherwise + */ + public HSVRange truncateRange() { + if (hueLow < 0) { + return new HSVRange(0, hueHigh, this); + } + return null; + } + + /** + * @param newHue The new hue for an existing HSVrange + * @param hRange The new range for an existing HSVRange + * @return A new HSVRange using the current Saturation and Values, with a new hue & hue range + */ + public HSVRange newHue(int newHue, int hRange) { + return new HSVRange(newHue, hRange, satLow, satHigh, valLow, valHigh); + } + + /** + * @return A Scalar for OpenCV use for color detection for the low end + */ + public Scalar lowEdge() { + return new Scalar(hueLow, satLow, valLow); + } + + /** + * @return A Scalar for OpenCV use for color detection for the high end + */ + public Scalar highEdge() { + return new Scalar(hueHigh, satHigh, valHigh); + } +} diff --git a/Vision/src/main/java/com/technototes/vision/subsystem/BasicVisionSubsystem.java b/Vision/src/main/java/com/technototes/vision/subsystem/BasicVisionSubsystem.java new file mode 100644 index 00000000..c5613a83 --- /dev/null +++ b/Vision/src/main/java/com/technototes/vision/subsystem/BasicVisionSubsystem.java @@ -0,0 +1,230 @@ +package com.technototes.vision.subsystem; + +import com.technototes.library.subsystem.Subsystem; +import com.technototes.vision.HSVRange; +import com.technototes.vision.hardware.Camera; +import org.opencv.core.Core; +import org.opencv.core.Mat; +import org.opencv.core.Rect; +import org.opencv.core.Scalar; +import org.opencv.imgproc.Imgproc; +import org.openftc.easyopencv.OpenCvCameraRotation; +import org.openftc.easyopencv.OpenCvPipeline; + +/** + * A vision streaming pipeline to enable vision processing during an opmode + */ +@SuppressWarnings("unused") +public abstract class BasicVisionSubsystem extends OpenCvPipeline implements Subsystem { + + /** + * The Camera object this subsystem is processing frames from + */ + protected Camera camera; + /** + * The width and height of the image requested from the camera + */ + protected int width, height; + /** + * The rotation applied to the image + */ + protected OpenCvCameraRotation rotation; + /** + * The current frame being processed (can be drawn on!) + */ + protected Mat curFrameRGB; + /** + * True iff the pipeline is properly set and running + */ + protected boolean pipelineSet; + + /** + * Create the subsystem with the Camera provided + * + * @param c The camera to process frames from + * @param w The width of the camera image + * @param h The height fo the camera image + * @param rot The rotation of the camera image + */ + public BasicVisionSubsystem(Camera c, int w, int h, OpenCvCameraRotation rot) { + camera = c; + width = w; + height = h; + rotation = rot; + curFrameRGB = null; + pipelineSet = false; + } + + /** + * Get the Camera device that frames are being processed from + * + * @return the Camera device in use + */ + protected Camera getRawDevice() { + return camera; + } + + /** + * Start the images coming from the camera + */ + protected void beginStreaming() { + camera.startStreaming(width, height, rotation); + } + + /** + * Turn on the camera and start visual processing + */ + public void startVisionPipeline() { + camera.setPipeline(this); + pipelineSet = true; + // The i -> lambda appears to be for *error reporting* so this line is silly: + camera.openCameraDeviceAsync(this::beginStreaming, i -> startVisionPipeline()); + } + + /** + * Turn off the camera and enable visual processing + */ + public void stopVisionPipeline() { + camera.setPipeline(null); + pipelineSet = false; + camera.closeCameraDeviceAsync(() -> { + /* Do we need to do anything to stop the vision pipeline? */ + }); + } + + /** + * Turn off the camera and stop visual processing + * + * @return this for chaining if you really want... + */ + public BasicVisionSubsystem startStreaming() { + beginStreaming(); + return this; + } + + /** + * Stop frame processing + * + * @return this PipelineSubsystem (for chaining) + */ + public BasicVisionSubsystem stopStreaming() { + if (pipelineSet) { + stopVisionPipeline(); + } + camera.stopStreaming(); + return this; + } + + // These are the three functions you need to implement. + // I use this so that you can edit your rectangles in realtime from the FtcDashboard. + // If you don't use FtcDashboard, just make an array of Rect's and be done with it. + // But really, you should be using FtcDashboard. It's much faster to get this right. + + /** + * @return How many rectangles are you checking + */ + public abstract int numRectangles(); + + /** + * Get the specific rectangle number + * + * @param rectNumber Which rectangle to return + * @return The rectangle that will be processed + */ + public abstract Rect getRect(int rectNumber); + + /** + * Process the particular rectangle (you probably want to call countPixelsOfColor ;) ) + * @param inputHSV The HSV rectangle to process + * @param rectNumber The rectangle this Mat is from within the overall image + */ + public abstract void runDetection(Mat inputHSV, int rectNumber); + + /** + * Override this to do something before a frame is processed + */ + protected void detectionStart() {} + + /** + * Override this to do something after a frame is processed + */ + protected void detectionEnd() {} + + /** + * Run processing on the frame provided. + * This invokes detectionStart, numRectangles, getRect, runDetection, and detectionEnd. + * You probably don't want to bother overriding it, unless you can't use the rectangle + * processing facilty as is. + * + * @param frame The RGB frame from the camera + */ + protected void detectionProcessing(Mat frame) { + // Put the input matrix in a member variable, so that other functions can draw on it + curFrameRGB = frame; + detectionStart(); + int count = numRectangles(); + for (int i = 0; i < count; i++) { + // First, slice the smaller rectangle out of the overall bitmap: + Rect r = getRect(i); + Mat subRectRGB = curFrameRGB.submat(r.y, r.y + r.height, r.x, r.x + r.width); + + // Next, convert the RGB image to HSV, because HUE is much easier to identify colors in + // The output is in 'customColorSpace' + Mat subRectHSV = new Mat(); + Imgproc.cvtColor(subRectRGB, subRectHSV, Imgproc.COLOR_RGB2HSV); + runDetection(subRectHSV, i); + } + detectionEnd(); + } + + @Override + public Mat processFrame(Mat input) { + detectionProcessing(input); + return input; + } + + public void init(Mat firstFrame) { + detectionProcessing(firstFrame); + } + + /** + * Count the number of pixels that are in the given range + * + * @param range The HSV range to look for + * @param imgHSV A sub-rectangle to count pixels in + * @param telemetryRGB The (optional) output RGB image (to help with debugging) + * @param xOffset The x-offset fo the subrectangle within the output RGB image + * @param yOffset The y-offset fo the subrectangle within the output RGB image + * @return The number of pixels that were found to be within the specified range + */ + protected int countPixelsOfColor(HSVRange range, Mat imgHSV, Mat telemetryRGB, int xOffset, int yOffset) { + int totalColorCount = 0; + // Since we might have a hue range of -15 to 15 to detect red, + // make the range 165 to 180 and run countColorsInRect with just that range first + HSVRange handleRedWrap = range.makeWrapAround(); + if (handleRedWrap != null) { + totalColorCount += countPixelsOfColor(handleRedWrap, imgHSV, telemetryRGB, xOffset, yOffset); + range = range.truncateRange(); + } + Scalar low = range.lowEdge(); + Scalar high = range.highEdge(); + // Check to see which pixels are between low and high, output into a boolean matrix Cr + Mat count = new Mat(); + Core.inRange(imgHSV, low, high, count); + totalColorCount = Core.countNonZero(count); + if (telemetryRGB != null) { + // TODO: It seems like there should be a more optimized way to do this. + for (int i = 0; i < count.width(); i++) { + for (int j = 0; j < count.height(); j++) { + if (count.get(j, i)[0] > 0) { + // Draw a dots on the image at this point - input was put into img + // The color choice makes things stripey, which makes it easier to identify + double[] colorToDraw = ((j + i) & 2) != 0 ? low.val : high.val; + telemetryRGB.put(j + yOffset, i + xOffset, colorToDraw); + } + } + } + } + return totalColorCount; + } +} diff --git a/Vision/src/main/java/com/technototes/vision/subsystem/PipelineSubsystem.java b/Vision/src/main/java/com/technototes/vision/subsystem/PipelineSubsystem.java deleted file mode 100644 index 63d98d35..00000000 --- a/Vision/src/main/java/com/technototes/vision/subsystem/PipelineSubsystem.java +++ /dev/null @@ -1,70 +0,0 @@ -package com.technototes.vision.subsystem; - -import com.technototes.library.subsystem.Subsystem; -import com.technototes.vision.hardware.Camera; -import org.openftc.easyopencv.OpenCvCameraRotation; - -/** - * A vision streaming pipeline to enable vision processing during an opmode - */ -@SuppressWarnings("unused") -public class PipelineSubsystem implements Subsystem { - - /** - * The Camera object this subsystem is processing frames from - */ - protected Camera camera; - - /** - * Create the subsystem with the Camera provided - * - * @param c The camera to process frames from - */ - public PipelineSubsystem(Camera c) { - camera = c; - } - - /** - * Get the Camera device that frames are being processed from - * - * @return the Camera device in use - */ - public Camera getDevice() { - return camera; - } - - /** - * This begins streaming frames from the camera - * - * @param width The width of the frame (constrained to a specific range, based on the camera device) - * @param height The height of the frame (constrained based on the camera device) - * @return this PipelineSubsystem (for chaining, I guess?) - */ - public PipelineSubsystem startStreaming(int width, int height) { - camera.startStreaming(width, height); - return this; - } - - /** - * This begins streaming frames from the camera - * - * @param width The width of the frame (constrained to a specific range, based on the camera device) - * @param height The height of the frame (consrained based on the camera device) - * @param rotation The rotation of the frame to acquire - * @return this PipelineSubsystem (for chaining, I guess?) - */ - public PipelineSubsystem startStreaming(int width, int height, OpenCvCameraRotation rotation) { - camera.startStreaming(width, height, rotation); - return this; - } - - /** - * Stop frame processing - * - * @return this PipelineSubsystem (for chaining) - */ - public PipelineSubsystem stopStreaming() { - camera.stopStreaming(); - return this; - } -} diff --git a/build.dependencies.gradle b/build.dependencies.gradle index 4cbf1215..3f94b0d1 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -6,9 +6,9 @@ repositories { } dependencies { - implementation 'org.firstinspires.ftc:RobotCore:9.0.0' - implementation 'org.firstinspires.ftc:RobotServer:9.0.0' - implementation 'org.firstinspires.ftc:Hardware:9.0.0' - implementation 'org.firstinspires.ftc:FtcCommon:9.0.0' + implementation 'org.firstinspires.ftc:RobotCore:9.0.1' + implementation 'org.firstinspires.ftc:RobotServer:9.0.1' + implementation 'org.firstinspires.ftc:Hardware:9.0.1' + implementation 'org.firstinspires.ftc:FtcCommon:9.0.1' implementation 'androidx.appcompat:appcompat:1.3.1' } diff --git a/docs/Path/com/technototes/path/command/MecanumDriveCommand.html b/docs/Path/com/technototes/path/command/MecanumDriveCommand.html index e3e0ba8a..13585d5c 100644 --- a/docs/Path/com/technototes/path/command/MecanumDriveCommand.html +++ b/docs/Path/com/technototes/path/command/MecanumDriveCommand.html @@ -79,7 +79,7 @@

Class MecanumDriveCommandcom.technototes.library.command.Command, Runnable, Supplier<com.technototes.library.command.Command.CommandState>
-
public class MecanumDriveCommand +
public class MecanumDriveCommand extends Object implements com.technototes.library.command.Command
@@ -180,25 +180,25 @@

Field Details

  • subsystem

    - +
  • x

    -
    public DoubleSupplier x
    +
    public DoubleSupplier x
  • y

    -
    public DoubleSupplier y
    +
    public DoubleSupplier y
  • r

    -
    public DoubleSupplier r
    +
    public DoubleSupplier r
  • @@ -212,7 +212,7 @@

    Constructor Details

  • MecanumDriveCommand

    -
    public MecanumDriveCommand(PathingMecanumDrivebaseSubsystem sub, + @@ -229,7 +229,7 @@

    Method Details

  • execute

    -
    public void execute()
    +
    public void execute()
    Specified by:
    execute in interface com.technototes.library.command.Command
    @@ -239,7 +239,7 @@

    execute

  • isFinished

    -
    public boolean isFinished()
    +
    public boolean isFinished()
    Specified by:
    isFinished in interface com.technototes.library.command.Command
    @@ -249,7 +249,7 @@

    isFinished

  • end

    -
    public void end(boolean cancel)
    +
    public void end(boolean cancel)
    Specified by:
    end in interface com.technototes.library.command.Command
    diff --git a/docs/Path/com/technototes/path/command/RegenerativeTrajectoryCommand.html b/docs/Path/com/technototes/path/command/RegenerativeTrajectoryCommand.html index 892cec25..b1616bfe 100644 --- a/docs/Path/com/technototes/path/command/RegenerativeTrajectoryCommand.html +++ b/docs/Path/com/technototes/path/command/RegenerativeTrajectoryCommand.html @@ -81,7 +81,7 @@

    Class Regenerative
    com.technototes.library.command.Command, Runnable, Supplier<com.technototes.library.command.Command.CommandState>


    -
    @@ -181,7 +181,7 @@

    Field Details

  • trajFunc

    -
    public Supplier<com.acmerobotics.roadrunner.trajectory.Trajectory> trajFunc
    +
    public Supplier<com.acmerobotics.roadrunner.trajectory.Trajectory> trajFunc
  • @@ -195,21 +195,21 @@

    Constructor Details

  • RegenerativeTrajectoryCommand

    -
    public RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, +
    public RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, Function<Function<com.acmerobotics.roadrunner.geometry.Pose2d,com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder>,com.acmerobotics.roadrunner.trajectory.Trajectory> t)
  • RegenerativeTrajectoryCommand

    -
    public RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, +
    public RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, Supplier<com.acmerobotics.roadrunner.trajectory.Trajectory> t)
  • RegenerativeTrajectoryCommand

    -
    public RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, +
    public RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, BiFunction<Function<com.acmerobotics.roadrunner.geometry.Pose2d,com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder>,T,com.acmerobotics.roadrunner.trajectory.Trajectory> t, T mux)
    @@ -217,7 +217,7 @@

    RegenerativeTrajectoryCommand

    -
    public RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, +
    public RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, Function<T,com.acmerobotics.roadrunner.trajectory.Trajectory> t, T mux)
  • @@ -233,7 +233,7 @@

    Method Details

  • initialize

    -
    public void initialize()
    +
    public void initialize()
    Specified by:
    initialize in interface com.technototes.library.command.Command
    diff --git a/docs/Path/com/technototes/path/command/TrajectorySequenceCommand.html b/docs/Path/com/technototes/path/command/TrajectorySequenceCommand.html index 1ec0a42c..9a807af7 100644 --- a/docs/Path/com/technototes/path/command/TrajectorySequenceCommand.html +++ b/docs/Path/com/technototes/path/command/TrajectorySequenceCommand.html @@ -258,7 +258,7 @@

    Method Details

  • initialize

    -
    public void initialize()
    +
    public void initialize()
    Specified by:
    initialize in interface com.technototes.library.command.Command
    @@ -268,7 +268,7 @@

    initialize

  • execute

    -
    public void execute()
    +
    public void execute()
    Specified by:
    execute in interface com.technototes.library.command.Command
    @@ -278,7 +278,7 @@

    execute

  • isFinished

    -
    public boolean isFinished()
    +
    public boolean isFinished()
    Specified by:
    isFinished in interface com.technototes.library.command.Command
    @@ -288,7 +288,7 @@

    isFinished

  • end

    -
    public void end(boolean cancel)
    +
    public void end(boolean cancel)
    Specified by:
    end in interface com.technototes.library.command.Command
    diff --git a/docs/Path/src-html/com/technototes/path/command/MecanumDriveCommand.html b/docs/Path/src-html/com/technototes/path/command/MecanumDriveCommand.html index c28fede6..643546db 100644 --- a/docs/Path/src-html/com/technototes/path/command/MecanumDriveCommand.html +++ b/docs/Path/src-html/com/technototes/path/command/MecanumDriveCommand.html @@ -18,47 +18,46 @@ 005import com.acmerobotics.roadrunner.geometry.Vector2d; 006import com.technototes.library.command.Command; 007import com.technototes.path.subsystem.PathingMecanumDrivebaseSubsystem; -008 -009import java.util.function.DoubleSupplier; -010 -011public class MecanumDriveCommand implements Command { -012 -013 public PathingMecanumDrivebaseSubsystem subsystem; -014 public DoubleSupplier x, y, r; -015 -016 public MecanumDriveCommand( -017 PathingMecanumDrivebaseSubsystem sub, -018 DoubleSupplier xSup, -019 DoubleSupplier ySup, -020 DoubleSupplier rSup -021 ) { -022 addRequirements(sub); -023 subsystem = sub; -024 x = xSup; -025 y = ySup; -026 r = rSup; -027 } -028 -029 @Override -030 public void execute() { -031 Vector2d input = new Vector2d(-y.getAsDouble() * subsystem.speed, -x.getAsDouble() * subsystem.speed) -032 .rotated(-subsystem.getExternalHeading()); -033 -034 subsystem.setWeightedDrivePower( -035 new Pose2d(input.getX(), input.getY(), -Math.pow(r.getAsDouble() * subsystem.speed, 3)) -036 ); -037 } -038 -039 @Override -040 public boolean isFinished() { -041 return false; -042 } -043 -044 @Override -045 public void end(boolean cancel) { -046 if (cancel) subsystem.setDriveSignal(new DriveSignal()); -047 } -048} +008import java.util.function.DoubleSupplier; +009 +010public class MecanumDriveCommand implements Command { +011 +012 public PathingMecanumDrivebaseSubsystem subsystem; +013 public DoubleSupplier x, y, r; +014 +015 public MecanumDriveCommand( +016 PathingMecanumDrivebaseSubsystem sub, +017 DoubleSupplier xSup, +018 DoubleSupplier ySup, +019 DoubleSupplier rSup +020 ) { +021 addRequirements(sub); +022 subsystem = sub; +023 x = xSup; +024 y = ySup; +025 r = rSup; +026 } +027 +028 @Override +029 public void execute() { +030 Vector2d input = new Vector2d(-y.getAsDouble() * subsystem.speed, -x.getAsDouble() * subsystem.speed) +031 .rotated(-subsystem.getExternalHeading()); +032 +033 subsystem.setWeightedDrivePower( +034 new Pose2d(input.getX(), input.getY(), -Math.pow(r.getAsDouble() * subsystem.speed, 3)) +035 ); +036 } +037 +038 @Override +039 public boolean isFinished() { +040 return false; +041 } +042 +043 @Override +044 public void end(boolean cancel) { +045 if (cancel) subsystem.setDriveSignal(new DriveSignal()); +046 } +047} diff --git a/docs/Path/src-html/com/technototes/path/command/RegenerativeTrajectoryCommand.html b/docs/Path/src-html/com/technototes/path/command/RegenerativeTrajectoryCommand.html index dd3029a8..9c441bf1 100644 --- a/docs/Path/src-html/com/technototes/path/command/RegenerativeTrajectoryCommand.html +++ b/docs/Path/src-html/com/technototes/path/command/RegenerativeTrajectoryCommand.html @@ -17,47 +17,46 @@ 004import com.acmerobotics.roadrunner.trajectory.Trajectory; 005import com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder; 006import com.technototes.path.subsystem.PathingMecanumDrivebaseSubsystem; -007 -008import java.util.function.BiFunction; -009import java.util.function.Function; -010import java.util.function.Supplier; -011 -012public class RegenerativeTrajectoryCommand extends TrajectoryCommand { -013 -014 public Supplier<Trajectory> trajFunc; -015 -016 public RegenerativeTrajectoryCommand( -017 PathingMecanumDrivebaseSubsystem sub, -018 Function<Function<Pose2d, TrajectoryBuilder>, Trajectory> t -019 ) { -020 super(sub, t); -021 trajFunc = () -> t.apply(sub::trajectoryBuilder); -022 } -023 -024 public RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, Supplier<Trajectory> t) { -025 super(sub, t); -026 trajFunc = t; -027 } -028 -029 public <T> RegenerativeTrajectoryCommand( -030 PathingMecanumDrivebaseSubsystem sub, -031 BiFunction<Function<Pose2d, TrajectoryBuilder>, T, Trajectory> t, -032 T mux -033 ) { -034 super(sub, t, mux); -035 trajFunc = () -> t.apply(sub::trajectoryBuilder, mux); -036 } -037 -038 public <T> RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, Function<T, Trajectory> t, T mux) { -039 super(sub, t, mux); -040 trajFunc = () -> t.apply(mux); -041 } -042 -043 @Override -044 public void initialize() { -045 subsystem.followTrajectoryAsync(trajFunc.get()); -046 } -047} +007import java.util.function.BiFunction; +008import java.util.function.Function; +009import java.util.function.Supplier; +010 +011public class RegenerativeTrajectoryCommand extends TrajectoryCommand { +012 +013 public Supplier<Trajectory> trajFunc; +014 +015 public RegenerativeTrajectoryCommand( +016 PathingMecanumDrivebaseSubsystem sub, +017 Function<Function<Pose2d, TrajectoryBuilder>, Trajectory> t +018 ) { +019 super(sub, t); +020 trajFunc = () -> t.apply(sub::trajectoryBuilder); +021 } +022 +023 public RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, Supplier<Trajectory> t) { +024 super(sub, t); +025 trajFunc = t; +026 } +027 +028 public <T> RegenerativeTrajectoryCommand( +029 PathingMecanumDrivebaseSubsystem sub, +030 BiFunction<Function<Pose2d, TrajectoryBuilder>, T, Trajectory> t, +031 T mux +032 ) { +033 super(sub, t, mux); +034 trajFunc = () -> t.apply(sub::trajectoryBuilder, mux); +035 } +036 +037 public <T> RegenerativeTrajectoryCommand(PathingMecanumDrivebaseSubsystem sub, Function<T, Trajectory> t, T mux) { +038 super(sub, t, mux); +039 trajFunc = () -> t.apply(mux); +040 } +041 +042 @Override +043 public void initialize() { +044 subsystem.followTrajectoryAsync(trajFunc.get()); +045 } +046} diff --git a/docs/Path/src-html/com/technototes/path/command/TrajectorySequenceCommand.html b/docs/Path/src-html/com/technototes/path/command/TrajectorySequenceCommand.html index ef9d1b2f..cfe8b533 100644 --- a/docs/Path/src-html/com/technototes/path/command/TrajectorySequenceCommand.html +++ b/docs/Path/src-html/com/technototes/path/command/TrajectorySequenceCommand.html @@ -58,32 +58,36 @@ 045 trajectory = t.apply(sub::trajectorySequenceBuilder, mux); 046 } 047 -048 public <T> TrajectorySequenceCommand(PathingMecanumDrivebaseSubsystem sub, Function<T, TrajectorySequence> t, T mux) { -049 addRequirements(sub); -050 subsystem = sub; -051 trajectory = t.apply(mux); -052 } -053 -054 @Override -055 public void initialize() { -056 subsystem.followTrajectorySequenceAsync(trajectory); -057 } -058 -059 @Override -060 public void execute() { -061 subsystem.update(); -062 } -063 -064 @Override -065 public boolean isFinished() { -066 return !subsystem.isBusy(); -067 } -068 -069 @Override -070 public void end(boolean cancel) { -071 if (cancel) subsystem.stop(); -072 } -073} +048 public <T> TrajectorySequenceCommand( +049 PathingMecanumDrivebaseSubsystem sub, +050 Function<T, TrajectorySequence> t, +051 T mux +052 ) { +053 addRequirements(sub); +054 subsystem = sub; +055 trajectory = t.apply(mux); +056 } +057 +058 @Override +059 public void initialize() { +060 subsystem.followTrajectorySequenceAsync(trajectory); +061 } +062 +063 @Override +064 public void execute() { +065 subsystem.update(); +066 } +067 +068 @Override +069 public boolean isFinished() { +070 return !subsystem.isBusy(); +071 } +072 +073 @Override +074 public void end(boolean cancel) { +075 if (cancel) subsystem.stop(); +076 } +077} diff --git a/docs/TechnoLib/allclasses-index.html b/docs/TechnoLib/allclasses-index.html index 60a3aaee..a0615610 100644 --- a/docs/TechnoLib/allclasses-index.html +++ b/docs/TechnoLib/allclasses-index.html @@ -1012,76 +1012,56 @@

    All Classes and Interfaces<

  • Log.NumberBarLogConfig
    -
    Log a number, but store it as a number bar
    +
    Annotations for configuring Logs
    Log.NumberSliderLogConfig.AllowList
    -   +
    Annotation for allowing Opmodes to log this item
    LogConfigLogConfig.DenyList
    -
    Annotations for configuring Logs
    +
    Annotation for denying Opmodes to log this item
    -
    -
    Annotation for Blacklisting Opmodes to log this item
    -
    - -
    +
    Annotation to completely disable the entry
    -
    + -
    +
    Annotation for determining when logged item will be sent to Telemetry
    - -
    -
    Annotation for Whitelisting Opmodes to log this item
    -
    -
    -   -
    - -
    -   -
    -
     
    diff --git a/docs/TechnoLib/com/technototes/library/control/CommandAxis.html b/docs/TechnoLib/com/technototes/library/control/CommandAxis.html index 5177ba68..88fe5f9e 100644 --- a/docs/TechnoLib/com/technototes/library/control/CommandAxis.html +++ b/docs/TechnoLib/com/technototes/library/control/CommandAxis.html @@ -84,7 +84,7 @@

    Class CommandAxis

    CommandInput<CommandAxis>, Enablable<ButtonBase>, Invertable<ButtonBase>, Periodic, BooleanSupplier, DoubleSupplier

    -
    public class CommandAxis +
    public class CommandAxis extends AxisBase implements CommandInput<CommandAxis>
    Class for command axis for the gamepad
    @@ -202,7 +202,7 @@

    Constructor Details

  • CommandAxis

    -
    public CommandAxis(DoubleSupplier supplier)
    +
    public CommandAxis(DoubleSupplier supplier)
    Make a command axis
    Parameters:
    @@ -213,7 +213,7 @@

    CommandAxis

  • CommandAxis

    -
    public CommandAxis(DoubleSupplier supplier, +
    public CommandAxis(DoubleSupplier supplier, double threshold)
    Make a command axis
    @@ -234,7 +234,7 @@

    Method Details

  • getInstance

    - +
    Description copied from interface: CommandInput
    Return instance of class parameter
    @@ -248,7 +248,7 @@

    getInstance

  • setTriggerThreshold

    -
    public CommandAxis setTriggerThreshold(double threshold)
    +
    public CommandAxis setTriggerThreshold(double threshold)
    Description copied from class: AxisBase
    Set threshold
    @@ -262,19 +262,19 @@

    setTriggerThreshold

  • schedulePressed

    - +
  • schedule

    - +
  • setInverted

    -
    public CommandAxis setInverted(boolean invert)
    +
    public CommandAxis setInverted(boolean invert)
    Description copied from interface: Invertable
    Set the inversion (true -> Is inverted, false -> Not inverted)
    @@ -292,13 +292,13 @@

    setInverted

  • getAsButton

    - +
  • getAsButton

    -
    public CommandButton getAsButton(double threshold)
    +
    public CommandButton getAsButton(double threshold)
  • diff --git a/docs/TechnoLib/com/technototes/library/control/CommandGamepad.html b/docs/TechnoLib/com/technototes/library/control/CommandGamepad.html index 51203e83..b0b07896 100644 --- a/docs/TechnoLib/com/technototes/library/control/CommandGamepad.html +++ b/docs/TechnoLib/com/technototes/library/control/CommandGamepad.html @@ -103,7 +103,7 @@

    Fields inherited from class com.technototes.library.control.GamepadBase

    -a, b, back, circle, cross, dpad, dpadDown, dpadLeft, dpadRight, dpadUp, leftBumper, leftStick, leftStickButton, leftStickX, leftStickY, leftTrigger, options, rightBumper, rightStick, rightStickButton, rightStickX, rightStickY, rightTrigger, share, square, start, triangle, x, y
  • +dpad, dpadDown, dpadLeft, dpadRight, dpadUp, leftBumper, leftStick, leftStickButton, leftStickX, leftStickY, leftTrigger, ps_circle, ps_cross, ps_options, ps_share, ps_square, ps_triangle, rightBumper, rightStick, rightStickButton, rightStickX, rightStickY, rightTrigger, xbox_a, xbox_b, xbox_back, xbox_start, xbox_x, xbox_y
  • diff --git a/docs/TechnoLib/com/technototes/library/control/GamepadBase.Button.html b/docs/TechnoLib/com/technototes/library/control/GamepadBase.Button.html index bb126056..b6feb1bf 100644 --- a/docs/TechnoLib/com/technototes/library/control/GamepadBase.Button.html +++ b/docs/TechnoLib/com/technototes/library/control/GamepadBase.Button.html @@ -109,37 +109,37 @@

    Enum Constant Summary

    Enum Constant
    Description
    - +
    -
    XBox A button
    +
    Left bumper button
    - +
    -
    XBox B button
    +
    Button when clicking the left stick
    - +
    -
    PS4/XBox Back button
    +
    PS4 Circle (O) button
    - +
    -
    PS4 Circle (O) button
    +
    PS4 Cross (X) button
    - +
    -
    PS4 Cross (X) button
    +
    PS4 Options button
    - +
    -
    Left bumper button
    +
    PS4 Share button
    - +
    -
    Button when clicking the left stick
    +
    PS4 Square button
    - +
    -
    PS4 Options button
    +
    PS4 Triangle button
    @@ -149,27 +149,27 @@

    Enum Constant Summary

    Button which clicking the right stick
    - +
    -
    PS4 Share button
    +
    XBox A button
    - +
    -
    PS4 Square button
    +
    XBox B button
    - +
    -
    PS4/XBox Start button
    +
    XBox Back button
    - +
    -
    PS4 Triangle button
    +
    XBox Start button
    - +
    XBox X button
    - +
    XBox Y button
    @@ -219,87 +219,87 @@

    Methods inherited from cl

    Enum Constant Details

    - +
    -
    The button objects for the PS4 game controller
    +
    The button objects for the XBox game controller
    - +
    -
    The button objects for the PS4 game controller
    +
    The button objects for the XBox game controller
    - +
    The button objects for the XBox game controller
    - +
    -
    The button objects for the PS4 game controller
    +
    The button objects for the XBox game controller
    - +
    The button objects for the XBox game controller
    - +
    The button objects for the XBox game controller
    @@ -424,86 +424,86 @@

    Field Details

      @@ -86,54 +86,29 @@

      Optional Element Summary

      Modifier and Type
      Optional Element
      Description
      - - -
      -
      The color for the tag for the boolean
      -
      - - -
      -
      The color for the false String
      -
      - +
      -
      The format for when the boolean returns false
      -
      - - -
      Store the string when the annotated method returns false
      -
      int
      - -
      -
      Store index for this annotation (position in telemetry)
      -
      - - +
      int
      +
      -
      Store the name for this annotation to be be beside
      +
      Store index for this annotation (position in telemetry)
      -
      int
      - + +
      -
      Store priority for this log entry (to pick the most wanted entry over others with same index)
      +
      Store the name for this annotation to be be beside
      - - +
      int
      +
      -
      The color for the true String
      +
      Store priority for this log entry (to pick the most wanted entry over others with same index)
      - +
      -
      The format for when the boolean returns true
      -
      - - -
      Store the string when the annotated method returns true
    @@ -151,7 +126,7 @@

    Element Details

  • index

    -
    int index
    +
    int index
    Store index for this annotation (position in telemetry)
    Returns:
    @@ -166,7 +141,7 @@

    index

  • priority

    - +
    Store priority for this log entry (to pick the most wanted entry over others with same index)
    Returns:
    @@ -181,7 +156,7 @@

    priority

  • trueValue

    - +
    Store the string when the annotated method returns true
    Returns:
    @@ -194,39 +169,9 @@

    trueValue

  • -
    -

    trueFormat

    - -
    The format for when the boolean returns true
    -
    -
    Returns:
    -
    The String format
    -
    -
    -
    Default:
    -
    "%s"
    -
    -
    -
  • -
  • -
    -

    trueColor

    - -
    The color for the true String
    -
    -
    Returns:
    -
    The color
    -
    -
    -
    Default:
    -
    NO_COLOR
    -
    -
    -
  • -
  • falseValue

    - +
    Store the string when the annotated method returns false
    Returns:
    @@ -239,39 +184,9 @@

    falseValue

  • -
    -

    falseFormat

    - -
    The format for when the boolean returns false
    -
    -
    Returns:
    -
    The String format
    -
    -
    -
    Default:
    -
    "%s"
    -
    -
    -
  • -
  • -
    -

    falseColor

    - -
    The color for the false String
    -
    -
    Returns:
    -
    The color
    -
    -
    -
    Default:
    -
    NO_COLOR
    -
    -
    -
  • -
  • name

    - +
    Store the name for this annotation to be be beside
    Returns:
    @@ -283,21 +198,6 @@

    name

  • -
  • -
    -

    color

    - -
    The color for the tag for the boolean
    -
    -
    Returns:
    -
    The color
    -
    -
    -
    Default:
    -
    NO_COLOR
    -
    -
    -
  • diff --git a/docs/TechnoLib/com/technototes/library/logger/Log.Logs.html b/docs/TechnoLib/com/technototes/library/logger/Log.Logs.html index 320e1432..0e81251c 100644 --- a/docs/TechnoLib/com/technototes/library/logger/Log.Logs.html +++ b/docs/TechnoLib/com/technototes/library/logger/Log.Logs.html @@ -74,7 +74,7 @@

    Annotation Interface Log
    @Documented @Retention(RUNTIME) @Target({FIELD,METHOD}) -public static @interface Log.Logs
    +public static @interface Log.Logs

    diff --git a/docs/TechnoLib/com/technototes/library/logger/Log.Number.html b/docs/TechnoLib/com/technototes/library/logger/Log.Number.html index e15a0f8d..5ebf0497 100644 --- a/docs/TechnoLib/com/technototes/library/logger/Log.Number.html +++ b/docs/TechnoLib/com/technototes/library/logger/Log.Number.html @@ -73,7 +73,7 @@

    Annotation Interface L
    +public static @interface Log.Number
    Log a number

    @@ -87,25 +87,15 @@

    Optional Element Summary

    Modifier and Type
    Optional Element
    Description
    - - +
    int
    +
    -
    The color for the tag for the number
    -
    -
    int
    - -
    Store index for this annotation (position in telemetry)
    - - -
    -
    Store the name for this annotation to be be beside
    -
    - - + +
    -
    The color for the number
    +
    Store the name for this annotation to be be beside
    int
    @@ -127,7 +117,7 @@

    Element Details

  • index

    -
    int index
    +
    int index
    Store index for this annotation (position in telemetry)
    Returns:
    @@ -142,7 +132,7 @@

    index

  • priority

    - +
    Store priority for this log entry (to pick the most wanted entry over others with same index)
    Returns:
    @@ -157,7 +147,7 @@

    priority

  • name

    - +
    Store the name for this annotation to be be beside
    Returns:
    @@ -169,36 +159,6 @@

    name

  • -
  • -
    -

    color

    - -
    The color for the tag for the number
    -
    -
    Returns:
    -
    The color
    -
    -
    -
    Default:
    -
    NO_COLOR
    -
    -
    -
  • -
  • -
    -

    numberColor

    - -
    The color for the number
    -
    -
    Returns:
    -
    The color
    -
    -
    -
    Default:
    -
    NO_COLOR
    -
    -
    -
  • diff --git a/docs/TechnoLib/com/technototes/library/logger/Log.NumberBar.html b/docs/TechnoLib/com/technototes/library/logger/Log.NumberBar.html deleted file mode 100644 index 188e93f1..00000000 --- a/docs/TechnoLib/com/technototes/library/logger/Log.NumberBar.html +++ /dev/null @@ -1,312 +0,0 @@ - - - - -Log.NumberBar (RobotLibrary API) - - - - - - - - - - - - - - -
    - -
    -
    - -
    - -

    Annotation Interface Log.NumberBar

    -
    -
    -
    -
    Enclosing class:
    -
    Log
    -
    -
    - -
    Log a number, but store it as a number bar
    -
    -
    -
      - -
    • -
      -

      Optional Element Summary

      -
      Optional Elements
      -
      -
      Modifier and Type
      -
      Optional Element
      -
      Description
      - - -
      -
      The color for the tag for the bar
      -
      - - -
      -
      The color for the filled in bar color
      -
      - - -
      -
      The color for the not filled in bar color
      -
      -
      int
      - -
      -
      Store index for this annotation (position in telemetry)
      -
      -
      double
      - -
      -
      Store the max for the number bar to scale to
      -
      -
      double
      - -
      -
      Store the min for the number bar to scale to
      -
      - - -
      -
      Store the name for this annotation to be be beside
      -
      - - -
      -
      The color for the bar outlines
      -
      -
      int
      - -
      -
      Store priority for this log entry (to pick the most wanted entry over others with same index)
      -
      -
      double
      - -
      -
      Store the scale for the number bar to scale to
      -
      -
      -
      -
    • -
    -
    -
    -
      - -
    • -
      -

      Element Details

      -
        -
      • -
        -

        index

        -
        int index
        -
        Store index for this annotation (position in telemetry)
        -
        -
        Returns:
        -
        The index
        -
        -
        -
        Default:
        -
        -1
        -
        -
        -
      • -
      • -
        -

        priority

        - -
        Store priority for this log entry (to pick the most wanted entry over others with same index)
        -
        -
        Returns:
        -
        The priority
        -
        -
        -
        Default:
        -
        -1
        -
        -
        -
      • -
      • -
        -

        min

        -
        double min
        -
        Store the min for the number bar to scale to
        -
        -
        Returns:
        -
        The min
        -
        -
        -
        Default:
        -
        -1.0
        -
        -
        -
      • -
      • -
        -

        max

        -
        double max
        -
        Store the max for the number bar to scale to
        -
        -
        Returns:
        -
        The max
        -
        -
        -
        Default:
        -
        1.0
        -
        -
        -
      • -
      • -
        -

        scale

        -
        double scale
        -
        Store the scale for the number bar to scale to
        -
        -
        Returns:
        -
        The scale
        -
        -
        -
        Default:
        -
        0.1
        -
        -
        -
      • -
      • -
        -

        name

        - -
        Store the name for this annotation to be be beside
        -
        -
        Returns:
        -
        The name as a string
        -
        -
        -
        Default:
        -
        ""
        -
        -
        -
      • -
      • -
        -

        color

        - -
        The color for the tag for the bar
        -
        -
        Returns:
        -
        The color
        -
        -
        -
        Default:
        -
        NO_COLOR
        -
        -
        -
      • -
      • -
        -

        completeBarColor

        - -
        The color for the filled in bar color
        -
        -
        Returns:
        -
        The color
        -
        -
        -
        Default:
        -
        NO_COLOR
        -
        -
        -
      • -
      • -
        -

        incompleteBarColor

        - -
        The color for the not filled in bar color
        -
        -
        Returns:
        -
        The color
        -
        -
        -
        Default:
        -
        NO_COLOR
        -
        -
        -
      • -
      • -
        -

        outline

        - -
        The color for the bar outlines
        -
        -
        Returns:
        -
        The color
        -
        -
        -
        Default:
        -
        NO_COLOR
        -
        -
        -
      • -
      -
      -
    • -
    -
    - -
    -
    -
    - - diff --git a/docs/TechnoLib/com/technototes/library/logger/Log.NumberSlider.html b/docs/TechnoLib/com/technototes/library/logger/Log.NumberSlider.html deleted file mode 100644 index e6e43ce3..00000000 --- a/docs/TechnoLib/com/technototes/library/logger/Log.NumberSlider.html +++ /dev/null @@ -1,311 +0,0 @@ - - - - -Log.NumberSlider (RobotLibrary API) - - - - - - - - - - - - - - -
    - -
    -
    - -
    - -

    Annotation Interface Log.NumberSlider

    -
    -
    -
    -
    Enclosing class:
    -
    Log
    -
    -
    - -
    -
    -
      - -
    • -
      -

      Optional Element Summary

      -
      Optional Elements
      -
      -
      Modifier and Type
      -
      Optional Element
      -
      Description
      - - -
      -
      The color for the tag for the slider
      -
      -
      int
      - -
      -
      Store index for this annotation (position in telemetry)
      -
      -
      double
      - -
      -
      Store the max for the number bar to scale to
      -
      -
      double
      - -
      -
      Store the min for the number bar to scale to
      -
      - - -
      -
      Store the name for this annotation to be be beside
      -
      - - -
      -
      The color for the slider outline
      -
      -
      int
      - -
      -
      Store priority for this log entry (to pick the most wanted entry over others with same index)
      -
      -
      double
      - -
      -
      Store the scale for the number bar to scale to
      -
      - - -
      -
      The color for the slider slide
      -
      - - -
      -
      The color for the slider background
      -
      -
      -
      -
    • -
    -
    -
    -
      - -
    • -
      -

      Element Details

      -
        -
      • -
        -

        index

        -
        int index
        -
        Store index for this annotation (position in telemetry)
        -
        -
        Returns:
        -
        The index
        -
        -
        -
        Default:
        -
        -1
        -
        -
        -
      • -
      • -
        -

        priority

        - -
        Store priority for this log entry (to pick the most wanted entry over others with same index)
        -
        -
        Returns:
        -
        The priority
        -
        -
        -
        Default:
        -
        -1
        -
        -
        -
      • -
      • -
        -

        min

        -
        double min
        -
        Store the min for the number bar to scale to
        -
        -
        Returns:
        -
        The min
        -
        -
        -
        Default:
        -
        -1.0
        -
        -
        -
      • -
      • -
        -

        max

        -
        double max
        -
        Store the max for the number bar to scale to
        -
        -
        Returns:
        -
        The max
        -
        -
        -
        Default:
        -
        1.0
        -
        -
        -
      • -
      • -
        -

        scale

        -
        double scale
        -
        Store the scale for the number bar to scale to
        -
        -
        Returns:
        -
        The scale
        -
        -
        -
        Default:
        -
        0.1
        -
        -
        -
      • -
      • -
        -

        name

        - -
        Store the name for this annotation to be be beside
        -
        -
        Returns:
        -
        The name as a string
        -
        -
        -
        Default:
        -
        ""
        -
        -
        -
      • -
      • -
        -

        color

        - -
        The color for the tag for the slider
        -
        -
        Returns:
        -
        The color
        -
        -
        -
        Default:
        -
        NO_COLOR
        -
        -
        -
      • -
      • -
        -

        sliderBackground

        - -
        The color for the slider background
        -
        -
        Returns:
        -
        The color
        -
        -
        -
        Default:
        -
        NO_COLOR
        -
        -
        -
      • -
      • -
        -

        outline

        - -
        The color for the slider outline
        -
        -
        Returns:
        -
        The color
        -
        -
        -
        Default:
        -
        NO_COLOR
        -
        -
        -
      • -
      • -
        -

        slider

        - -
        The color for the slider slide
        -
        -
        Returns:
        -
        The color
        -
        -
        -
        Default:
        -
        NO_COLOR
        -
        -
        -
      • -
      -
      -
    • -
    -
    - -
    -
    -
    - - diff --git a/docs/TechnoLib/com/technototes/library/logger/Log.html b/docs/TechnoLib/com/technototes/library/logger/Log.html index 44cdc9f3..8e7813c3 100644 --- a/docs/TechnoLib/com/technototes/library/logger/Log.html +++ b/docs/TechnoLib/com/technototes/library/logger/Log.html @@ -71,7 +71,7 @@

    Annotation Interface Log

    @Repeatable(Logs.class) @Retention(RUNTIME) @Target({FIELD,LOCAL_VARIABLE,METHOD}) -public @interface Log +public @interface Log
    The root annotation for annotation logging, also doubles as a basic string log
    @@ -96,14 +96,6 @@

    Nested Class Summary

    Log a number
    -
    static @interface 
    - -
    -
    Log a number, but store it as a number bar
    -
    -
    static @interface 
    - -
     
  • @@ -116,16 +108,6 @@

    Optional Element Summary

    Modifier and Type
    Optional Element
    Description
    - - -
    -
    The color for the tag for the entry
    -
    - - -
    -
    The color for the entry
    -
    @@ -161,7 +143,7 @@

    Element Details

  • index

    -
    int index
    +
    int index
    Store index for this annotation (position in telemetry)
    Returns:
    @@ -176,7 +158,7 @@

    index

  • priority

    - +
    Store priority for this log entry (to pick the most wanted entry over others with same index)
    Returns:
    @@ -191,7 +173,7 @@

    priority

  • name

    - +
    Store the name for this annotation to be be beside
    Returns:
    @@ -206,7 +188,7 @@

    name

  • format

    - +
    The format for the logged String
    Returns:
    @@ -218,36 +200,6 @@

    format

  • -
  • -
    -

    entryColor

    - -
    The color for the entry
    -
    -
    Returns:
    -
    The color
    -
    -
    -
    Default:
    -
    NO_COLOR
    -
    -
    -
  • -
  • -
    -

    color

    - -
    The color for the tag for the entry
    -
    -
    Returns:
    -
    The color
    -
    -
    -
    Default:
    -
    NO_COLOR
    -
    -
    -
  • diff --git a/docs/TechnoLib/com/technototes/library/logger/LogConfig.Blacklist.html b/docs/TechnoLib/com/technototes/library/logger/LogConfig.AllowList.html similarity index 92% rename from docs/TechnoLib/com/technototes/library/logger/LogConfig.Blacklist.html rename to docs/TechnoLib/com/technototes/library/logger/LogConfig.AllowList.html index 493cbdd9..2673237f 100644 --- a/docs/TechnoLib/com/technototes/library/logger/LogConfig.Blacklist.html +++ b/docs/TechnoLib/com/technototes/library/logger/LogConfig.AllowList.html @@ -2,10 +2,10 @@ -LogConfig.Blacklist (RobotLibrary API) +LogConfig.AllowList (RobotLibrary API) - + @@ -63,7 +63,7 @@
    -

    Annotation Interface LogConfig.Blacklist

    +

    Annotation Interface LogConfig.AllowList

    @@ -73,8 +73,8 @@

    Annotation In
    -
    Annotation for Blacklisting Opmodes to log this item
    +public static @interface LogConfig.AllowList

  • +
    Annotation for allowing Opmodes to log this item
      @@ -90,7 +90,7 @@

      Required Element Summary

      Class<?>[]
      -
      The blacklisted opmodes
      +
      The allowed opmodes
    @@ -107,8 +107,8 @@

    Element Details

  • value

    -
    Class<?>[] value
    -
    The blacklisted opmodes
    +
    Class<?>[] value
    +
    The allowed opmodes
    Returns:
    Opmode Classes
    diff --git a/docs/TechnoLib/com/technototes/library/logger/LogConfig.Whitelist.html b/docs/TechnoLib/com/technototes/library/logger/LogConfig.DenyList.html similarity index 92% rename from docs/TechnoLib/com/technototes/library/logger/LogConfig.Whitelist.html rename to docs/TechnoLib/com/technototes/library/logger/LogConfig.DenyList.html index 68d77335..8d81a1a6 100644 --- a/docs/TechnoLib/com/technototes/library/logger/LogConfig.Whitelist.html +++ b/docs/TechnoLib/com/technototes/library/logger/LogConfig.DenyList.html @@ -2,10 +2,10 @@ -LogConfig.Whitelist (RobotLibrary API) +LogConfig.DenyList (RobotLibrary API) - + @@ -63,7 +63,7 @@
    -

    Annotation Interface LogConfig.Whitelist

    +

    Annotation Interface LogConfig.DenyList

    @@ -73,8 +73,8 @@

    Annotation In
    -
    Annotation for Whitelisting Opmodes to log this item
    +public static @interface LogConfig.DenyList +
    Annotation for denying Opmodes to log this item

      @@ -90,7 +90,7 @@

      Required Element Summary

      Class<?>[]
      -
      The whitelisted opmodes
      +
      The denied opmodes
    @@ -107,8 +107,8 @@

    Element Details

  • value

    -
    Class<?>[] value
    -
    The whitelisted opmodes
    +
    Class<?>[] value
    +
    The denied opmodes
    Returns:
    Opmode Classes
    diff --git a/docs/TechnoLib/com/technototes/library/logger/LogConfig.html b/docs/TechnoLib/com/technototes/library/logger/LogConfig.html index 7598ae48..045bac53 100644 --- a/docs/TechnoLib/com/technototes/library/logger/LogConfig.html +++ b/docs/TechnoLib/com/technototes/library/logger/LogConfig.html @@ -83,24 +83,24 @@

    Nested Class Summary

    Class
    Description
    static @interface 
    - +
    -
    Annotation for Blacklisting Opmodes to log this item
    +
    Annotation for allowing Opmodes to log this item
    static @interface 
    - +
    -
    Annotation to completely disable the entry
    +
    Annotation for denying Opmodes to log this item
    static @interface 
    - +
    -
    Annotation for determining when logged item will be sent to Telemetry
    +
    Annotation to completely disable the entry
    static @interface 
    - +
    -
    Annotation for Whitelisting Opmodes to log this item
    +
    Annotation for determining when logged item will be sent to Telemetry
    diff --git a/docs/TechnoLib/com/technototes/library/logger/Logger.html b/docs/TechnoLib/com/technototes/library/logger/Logger.html index 75854ac7..4eabcd91 100644 --- a/docs/TechnoLib/com/technototes/library/logger/Logger.html +++ b/docs/TechnoLib/com/technototes/library/logger/Logger.html @@ -76,7 +76,7 @@

    Class Logger


    -
    public class Logger +
    public class Logger extends Object
    The class to manage logging
    @@ -167,19 +167,19 @@

    Field Details

  • runEntries

    -
    public Entry<?>[] runEntries
    +
    public Entry<?>[] runEntries
  • initEntries

    -
    public Entry<?>[] initEntries
    +
    public Entry<?>[] initEntries
  • captionDivider

    -
    public char captionDivider
    +
    public char captionDivider
    The divider between the tag and the entry for telemetry (default ':')
  • @@ -194,7 +194,7 @@

    Constructor Details

  • Logger

    -
    public Logger(com.qualcomm.robotcore.eventloop.opmode.OpMode op)
    +
    public Logger(com.qualcomm.robotcore.eventloop.opmode.OpMode op)
    Instantiate the logger
    Parameters:
    @@ -213,21 +213,21 @@

    Method Details

  • runUpdate

    -
    public void runUpdate()
    +
    public void runUpdate()
    Update the logged run items in temeletry
  • initUpdate

    -
    public void initUpdate()
    +
    public void initUpdate()
    Update the logged init items in temeletry
  • repeat

    -
    public static String repeat(String s, +
    public static String repeat(String s, int num)
    Repeat a String
    diff --git a/docs/TechnoLib/com/technototes/library/logger/entry/BooleanEntry.html b/docs/TechnoLib/com/technototes/library/logger/entry/BooleanEntry.html index 2107e10d..cd653280 100644 --- a/docs/TechnoLib/com/technototes/library/logger/entry/BooleanEntry.html +++ b/docs/TechnoLib/com/technototes/library/logger/entry/BooleanEntry.html @@ -93,7 +93,7 @@

    Class BooleanEntry

    Field Summary

    Fields inherited from class com.technototes.library.logger.entry.Entry

    -color, name, priority, supplier, tag, x
    +name, priority, supplier, x
  • @@ -104,16 +104,11 @@

    Constructor Summary

    Constructor
    Description
    -
    BooleanEntry(String n, +
    BooleanEntry(String n, Supplier<Boolean> s, int index, String wt, - String wf, - Color c, - String tf, - String ff, - Color tc, - Color fc)
    + String wf)
     
    @@ -139,7 +134,7 @@

    Method Summary

    Methods inherited from class com.technototes.library.logger.entry.Entry

    -get, getIndex, getName, getPriority, getTag, setIndex, setPriority
    +get, getIndex, getName, getPriority, setIndex, setPriority

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
    @@ -155,18 +150,13 @@

    Methods inherited from cl

    Constructor Details

    @@ -180,7 +170,7 @@

    Method Details

  • toString

    -
    public String toString()
    +
    public String toString()
    Description copied from class: Entry
    The String for the logged item
    diff --git a/docs/TechnoLib/com/technototes/library/logger/entry/Entry.html b/docs/TechnoLib/com/technototes/library/logger/entry/Entry.html index e57b77b7..bb0f2971 100644 --- a/docs/TechnoLib/com/technototes/library/logger/entry/Entry.html +++ b/docs/TechnoLib/com/technototes/library/logger/entry/Entry.html @@ -88,7 +88,7 @@

    Class Entry<T>

    BooleanEntry, NumberEntry, StringEntry

    -
    public abstract class Entry<T> +
    public abstract class Entry<T> extends Object implements Supplier<T>
    The root class for logging entries
    @@ -104,30 +104,20 @@

    Field Summary

    Modifier and Type
    Field
    Description
    -
    protected Color
    - +
    protected String
    +
    -
    Color to display
    -
    -
    protected String
    - -
    The name of the Entry
    -
    protected int
    - -
    -
    The priority (in the telemetry list) of the entry
    -
    -
    protected Supplier<T>
    - +
    protected int
    +
    -
    The function called to get the value to display
    +
    The priority (in the telemetry list) of the entry
    -
    protected String
    - +
    protected Supplier<T>
    +
    -
    String to use a 'header' (calculated from name and color)
    +
    The function called to get the value to display
    protected int
    @@ -145,12 +135,11 @@

    Constructor Summary

    Constructor
    Description
    -
    Entry(String n, +
    Entry(String n, Supplier<T> s, - int index, - Color c)
    + int index)
    -
    Create an entry with name, value, index, and color
    +
    Create an entry with name, value, index
    @@ -177,31 +166,26 @@

    Method Summary

    -
    Get the name (unformatted tag)
    +
    Get the name
    int
    Get Priority for the entry
    - - + +
    setIndex(int i)
    -
    The tag for the entry
    -
    - -
    setIndex(int i)
    -
    Set index
    - -
    setPriority(int p)
    -
    + +
    setPriority(int p)
    +
    Set's the priority for this log line (handy for telemetry overflow)
    - - -
    + + +
    The String for the logged item
    @@ -224,45 +208,31 @@

    Field Details

  • x

    -
    protected int x
    +
    protected int x
    The index (in the list) of the entry
  • priority

    -
    protected int priority
    +
    protected int priority
    The priority (in the telemetry list) of the entry
  • supplier

    -
    protected Supplier<T> supplier
    +
    protected Supplier<T> supplier
    The function called to get the value to display
  • name

    -
    protected String name
    +
    protected String name
    The name of the Entry
  • -
  • -
    -

    tag

    -
    protected String tag
    -
    String to use a 'header' (calculated from name and color)
    -
    -
  • -
  • -
    -

    color

    -
    protected Color color
    -
    Color to display
    -
    -
  • @@ -272,19 +242,17 @@

    color

    Constructor Details

    diff --git a/docs/TechnoLib/index-all.html b/docs/TechnoLib/index-all.html index 6f766cc2..0771b53e 100644 --- a/docs/TechnoLib/index-all.html +++ b/docs/TechnoLib/index-all.html @@ -81,34 +81,6 @@

    Index

    >Constant Field Values

    A

    -
    - a - - Variable in class com.technototes.library.control.GamepadBase -
    -
    -
    The button objects for the XBox game controller
    -
    -
    - A - - Enum constant in enum class com.technototes.library.control.GamepadBase.Button -
    -
    -
    XBox A button
    -
    A

    B

    -
    - b - - Variable in class com.technototes.library.control.GamepadBase -
    -
    -
    The button objects for the XBox game controller
    -
    -
    - B - - Enum constant in enum class com.technototes.library.control.GamepadBase.Button -
    -
    -
    XBox B button
    -
    -
    - back - - Variable in class com.technototes.library.control.GamepadBase -
    -
    -
    The button objects for the XBox game controller
    -
    -
    - BACK - - Enum constant in enum class com.technototes.library.control.GamepadBase.Button -
    -
    -
    PS4/XBox Back button
    -
    B
     
    BooleanEntry(String, Supplier<Boolean>, int, String, String, Color, String, - String, Color, Color)BooleanEntry(String, Supplier<Boolean>, int, String, String) - Constructor for class com.technototes.library.logger.entry.C *think* this will wwait until b is true -
    - circle - - Variable in class com.technototes.library.control.GamepadBase -
    -
    -
    The button objects for the PS4 game controller
    -
    -
    - CIRCLE - - Enum constant in enum class com.technototes.library.control.GamepadBase.Button -
    -
    -
    PS4 Circle (O) button
    -
    C
    Command gamepad objects
    -
    - color - - Variable in class com.technototes.library.logger.entry.Entry -
    -
    -
    Color to display
    -
    -
    - color() - - Element in annotation interface com.technototes.library.logger.Log.Boolean -
    -
    -
    The color for the tag for the boolean
    -
    -
    - color() - - Element in annotation interface com.technototes.library.logger.Log -
    -
    -
    The color for the tag for the entry
    -
    -
    - color() - - Element in annotation interface com.technototes.library.logger.Log.Number -
    -
    -
    The color for the tag for the number
    -
    -
    - color() - - Element in annotation interface com.technototes.library.logger.Log.NumberBar -
    -
    -
    The color for the tag for the bar
    -
    -
    - color() - - Element in annotation interface com.technototes.library.logger.Log.NumberSlider -
    -
    -
    The color for the tag for the slider
    -
    C
    This is a "singleton" object for scheduling commands.
    -
    - completeBarColor() - - Element in annotation interface com.technototes.library.logger.Log.NumberBar -
    -
    -
    The color for the filled in bar color
    -
    C
    Deprecated
    -
    - cross - - Variable in class com.technototes.library.control.GamepadBase -
    -
    -
    The button objects for the PS4 game controller
    -
    -
    - CROSS - - Enum constant in enum class com.technototes.library.control.GamepadBase.Button -
    -
    -
    PS4 Cross (X) button
    -
    E
    Entry(String, Supplier<T>, int, Color)Entry(String, Supplier<T>, int) - Constructor for class com.technototes.library.logger.entry.E >
    -
    Create an entry with name, value, index, and color
    -
    -
    - entryColor() - - Element in annotation interface com.technototes.library.logger.Log -
    -
    -
    The color for the entry
    +
    Create an entry with name, value, index
    E

    F

    -
    - falseColor() - - Element in annotation interface com.technototes.library.logger.Log.Boolean -
    -
    -
    The color for the false String
    -
    -
    - falseFormat() - - Element in annotation interface com.technototes.library.logger.Log.Boolean -
    -
    -
    The format for when the boolean returns false
    -
    G
    Returns the stick's distance from the center
    -
    - getDouble() - - Method in class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     
    G >
    -
    Get the name (unformatted tag)
    +
    Get the name
    G
     
    getTag()getTargetPosition() - - Method in class com.technototes.library.logger.entry.Entry -
    -
    -
    The tag for the entry
    -
    -
    - getTargetPosition() - - Method in class com.technototes.library.hardware.servo.ServoProfilerServoProfiler
     
    @@ -6700,21 +6377,6 @@

    I

    This is duplicated in the IMU class
    -
    - incompleteBarColor() - - Element in annotation interface com.technototes.library.logger.Log.NumberBar -
    -
    -
    The color for the not filled in bar color
    -
    I
    Store index for this annotation (position in telemetry)
    -
    - index() - - Element in annotation interface com.technototes.library.logger.Log.NumberBar -
    -
    -
    Store index for this annotation (position in telemetry)
    -
    -
    - index() - - Element in annotation interface com.technototes.library.logger.Log.NumberSlider -
    -
    -
    Store index for this annotation (position in telemetry)
    -
    L
    Log.NumberBarLogConfig - Annotation Interface in L >
    -
    Log a number, but store it as a number bar
    +
    Annotations for configuring Logs
    Log.NumberSlider - - Annotation Interface in - com.technototes.library.logger -
    -
     
    -
    - LogConfigLogConfig.AllowList - Annotation Interface in L >
    -
    Annotations for configuring Logs
    +
    Annotation for allowing Opmodes to log this item
    LogConfig.BlacklistLogConfig.DenyList - Annotation Interface in L >
    -
    Annotation for Blacklisting Opmodes to log this item
    +
    Annotation for denying Opmodes to log this item
    L Annotation for determining when logged item will be sent to Telemetry -
    - LogConfig.Whitelist - - Annotation Interface in - com.technototes.library.logger -
    -
    -
    Annotation for Whitelisting Opmodes to log this item
    -
    M >
     
    -
    - max - - Variable in class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     
    max - Variable in class com.technototes.library.util.M
    The maximum value of the range
    -
    - max() - - Method in class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     
    -
    - max() - - Element in annotation interface com.technototes.library.logger.Log.NumberBar -
    -
    -
    Store the max for the number bar to scale to
    -
    -
    - max() - - Element in annotation interface com.technototes.library.logger.Log.NumberSlider -
    -
    -
    Store the max for the number bar to scale to
    -
    M
    Get the 'middle' of the range
    -
    - min - - Variable in class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     
    min - Variable in class com.technototes.library.util.M
    The minimum value of the range
    -
    - min() - - Method in class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     
    -
    - min() - - Element in annotation interface com.technototes.library.logger.Log.NumberBar -
    -
    -
    Store the min for the number bar to scale to
    -
    -
    - min() - - Element in annotation interface com.technototes.library.logger.Log.NumberSlider -
    -
    -
    Store the min for the number bar to scale to
    -
    N
    Store the name for this annotation to be be beside
    -
    - name() - - Element in annotation interface com.technototes.library.logger.Log.NumberBar -
    -
    -
    Store the name for this annotation to be be beside
    -
    -
    - name() - - Element in annotation interface com.technototes.library.logger.Log.NumberSlider -
    -
    -
    Store the name for this annotation to be be beside
    -
    N
    deprecated
    -
    - NumberBarEntry - - Class in - com.technototes.library.logger.entry -
    -
     
    -
    - NumberBarEntry(String, Supplier<Number>, int, Number, Number, Number, Color, - Color, Color, Color) - - Constructor for class com.technototes.library.logger.entry.NumberBarEntry -
    -
     
    N >
     
    -
    - numberColor() - - Element in annotation interface com.technototes.library.logger.Log.Number -
    -
    -
    The color for the number
    -
    N
     
    NumberEntry(String, Supplier<Number>, int, Color) - - Constructor for class com.technototes.library.logger.entry.NumberEntry -
    -
     
    -
    - NumberEntry(String, Supplier<Number>, int, Color, Color)NumberEntry(String, Supplier<Number>, int) - Constructor for class com.technototes.library.logger.entry.N >
     
    -
    - NumberSliderEntry - - Class in - com.technototes.library.logger.entry -
    -
     
    -
    - NumberSliderEntry(String, Supplier<Number>, int, Number, Number, Number, - Color, Color, Color, Color) - - Constructor for class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     

    O

    @@ -9307,76 +8687,16 @@

    O

    Set the distance unit
    - optionsORANGE - - Variable in class com.technototes.library.control.GamepadBaseColor
    -
    -
    The button objects for the PS4 game controller
    -
    -
    - OPTIONS - - Enum constant in enum class com.technototes.library.control.GamepadBase.Button -
    -
    -
    PS4 Options button
    -
    -
    - ORANGE - - Enum constant in enum class com.technototes.library.util.Color -
    -
     
    -
    - outline() - - Element in annotation interface com.technototes.library.logger.Log.NumberBar -
    -
    -
    The color for the bar outlines
    -
    -
    - outline() - - Element in annotation interface com.technototes.library.logger.Log.NumberSlider -
    -
    -
    The color for the slider outline
    -
    +
     
    P
    deprecated
    -
    - primary - - Variable in class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     
    P same index) -
    - priority() - - Element in annotation interface com.technototes.library.logger.Log.NumberBar -
    -
    -
    - Store priority for this log entry (to pick the most wanted entry over others with - same index) -
    -
    -
    - priority() - - Element in annotation interface com.technototes.library.logger.Log.NumberSlider -
    -
    -
    - Store priority for this log entry (to pick the most wanted entry over others with - same index) -
    -
    priority()P >
     
    +
    + ps_circle + - Variable in class com.technototes.library.control.GamepadBase +
    +
    +
    The button objects for the PS4 game controller
    +
    +
    + PS_CIRCLE + - Enum constant in enum class com.technototes.library.control.GamepadBase.Button +
    +
    +
    PS4 Circle (O) button
    +
    +
    + ps_cross + - Variable in class com.technototes.library.control.GamepadBase +
    +
    +
    The button objects for the PS4 game controller
    +
    +
    + PS_CROSS + - Enum constant in enum class com.technototes.library.control.GamepadBase.Button +
    +
    +
    PS4 Cross (X) button
    +
    +
    + ps_options + - Variable in class com.technototes.library.control.GamepadBase +
    +
    +
    The button objects for the PS4 game controller
    +
    +
    + PS_OPTIONS + - Enum constant in enum class com.technototes.library.control.GamepadBase.Button +
    +
    +
    PS4 Options button
    +
    +
    + ps_share + - Variable in class com.technototes.library.control.GamepadBase +
    +
    +
    The button objects for the PS4 game controller
    +
    +
    + PS_SHARE + - Enum constant in enum class com.technototes.library.control.GamepadBase.Button +
    +
    +
    PS4 Share button
    +
    +
    + ps_square + - Variable in class com.technototes.library.control.GamepadBase +
    +
    +
    The button objects for the PS4 game controller
    +
    +
    + PS_SQUARE + - Enum constant in enum class com.technototes.library.control.GamepadBase.Button +
    +
    +
    PS4 Square button
    +
    +
    + ps_triangle + - Variable in class com.technototes.library.control.GamepadBase +
    +
    +
    The button objects for the PS4 game controller
    +
    +
    + PS_TRIANGLE + - Enum constant in enum class com.technototes.library.control.GamepadBase.Button +
    +
    +
    PS4 Triangle button
    +
    PURPLES
    scalescale(double) - - Variable in class com.technototes.library.logger.entry.NumberSliderEntryRange
    -
     
    +
    +
    Scale the range by a given value
    +
    scale() - - Method in class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     
    -
    - scale() - - Element in annotation interface com.technototes.library.logger.Log.NumberBar -
    -
    -
    Store the scale for the number bar to scale to
    -
    -
    - scale() - - Element in annotation interface com.technototes.library.logger.Log.NumberSlider -
    -
    -
    Store the scale for the number bar to scale to
    -
    -
    - scale(double) - - Method in class com.technototes.library.util.Range -
    -
    -
    Scale the range by a given value
    -
    -
    - scalePWM(double, double)scalePWM(double, double) - Method in class com.technototes.library.hardware.servo.S started *and* 'additionalCondition' is also true. -
    - secondary - - Variable in class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     
    S
    Deprecated.
      -
    - share - - Variable in class com.technototes.library.control.GamepadBase -
    -
    -
    The button objects for the PS4 game controller
    -
    -
    - SHARE - - Enum constant in enum class com.technototes.library.control.GamepadBase.Button -
    -
    -
    PS4 Share button
    -
    S
    Delay the command for some time
    -
    - slider() - - Element in annotation interface com.technototes.library.logger.Log.NumberSlider -
    -
    -
    The color for the slider slide
    -
    -
    - sliderBackground() - - Element in annotation interface com.technototes.library.logger.Log.NumberSlider -
    -
    -
    The color for the slider background
    -
    S
    Deprecated.
      -
    - square - - Variable in class com.technototes.library.control.GamepadBase -
    -
    -
    The button objects for the PS4 game controller
    -
    -
    - SQUARE - - Enum constant in enum class com.technototes.library.control.GamepadBase.Button -
    -
    -
    PS4 Square button
    -
    -
    - start - - Variable in class com.technototes.library.control.GamepadBase -
    -
    -
    The button objects for the XBox game controller
    -
    S
    Deprecated.
      -
    - START - - Enum constant in enum class com.technototes.library.control.GamepadBase.Button -
    -
    -
    PS4/XBox Start button
    -
    S
     
    StringEntry(String, Supplier<String>, int, Color, String, Color)StringEntry(String, Supplier<String>, int, String) - Constructor for class com.technototes.library.logger.entry.S

    T

    -
    - tag - - Variable in class com.technototes.library.logger.entry.Entry -
    -
    -
    String to use a 'header' (calculated from name and color)
    -
    T
    Forcefully halt the opmode
    -
    - tertiary - - Variable in class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     
    T
    The String for the logged item
    -
    - toString() - - Method in class com.technototes.library.logger.entry.NumberBarEntry -
    -
     
    T >
     
    -
    - toString() - - Method in class com.technototes.library.logger.entry.NumberSliderEntry -
    -
     
    T >
     
    -
    - triangle - - Variable in class com.technototes.library.control.GamepadBase -
    -
    -
    The button objects for the PS4 game controller
    -
    -
    - TRIANGLE - - Enum constant in enum class com.technototes.library.control.GamepadBase.Button -
    -
    -
    PS4 Triangle button
    -
    -
    - trueColor() - - Element in annotation interface com.technototes.library.logger.Log.Boolean -
    -
    -
    The color for the true String
    -
    -
    - trueFormat() - - Element in annotation interface com.technototes.library.logger.Log.Boolean -
    -
    -
    The format for when the boolean returns true
    -
    V
     
    value() - Element in annotation interface com.technototes.library.logger.LogConfig.BlacklistLogConfig.AllowList
    -
    The blacklisted opmodes
    +
    The allowed opmodes
    value() - Element in annotation interface com.technototes.library.logger.LogConfig.WhitelistLogConfig.DenyList
    -
    The whitelisted opmodes
    +
    The denied opmodes
    W

    X

    - x + - Variable in class com.technototes.library.logger.entry.Entry +
    +
    +
    The index (in the list) of the entry
    +
    +
    + xAxis + - Variable in class com.technototes.library.control.GamepadStick +
    +
    +
    The objects for the stick axis
    +
    +
    + xbox_a - Variable in class com.technototes.library.control.X
    The button objects for the XBox game controller
    - xXBOX_A - - Variable in class com.technototes.library.logger.entry.EntryGamepadBase.Button
    -
    The index (in the list) of the entry
    +
    XBox A button
    Xxbox_b + - Variable in class com.technototes.library.control.GamepadBase +
    +
    +
    The button objects for the XBox game controller
    +
    +
    + XBOX_B - Enum constant in enum class com.technototes.library.control.X >
    -
    XBox X button
    +
    XBox B button
    xAxisxbox_back - Variable in class com.technototes.library.control.GamepadStickGamepadBase
    -
    The objects for the stick axis
    +
    The button objects for the XBox game controller
    -
    -

    Y

    -
    - yXBOX_BACK + - Enum constant in enum class com.technototes.library.control.GamepadBase.Button +
    +
    +
    XBox Back button
    +
    +
    + xbox_start - Variable in class com.technototes.library.control.Y
    YXBOX_START + - Enum constant in enum class com.technototes.library.control.GamepadBase.Button +
    +
    +
    XBox Start button
    +
    +
    + xbox_x + - Variable in class com.technototes.library.control.GamepadBase +
    +
    +
    The button objects for the XBox game controller
    +
    +
    + XBOX_X + - Enum constant in enum class com.technototes.library.control.GamepadBase.Button +
    +
    +
    XBox X button
    +
    +
    + xbox_y + - Variable in class com.technototes.library.control.GamepadBase +
    +
    +
    The button objects for the XBox game controller
    +
    +
    + XBOX_Y - Enum constant in enum class com.technototes.library.control.Y
    XBox Y button
    +
    +

    Y

    +
    , int, String, String, Color, String, String, Color, Color)', - u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int,java.lang.String,java.lang.String,com.technototes.library.util.Color,java.lang.String,java.lang.String,com.technototes.library.util.Color,com.technototes.library.util.Color)', + l: 'BooleanEntry(String, Supplier, int, String, String)', + u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int,java.lang.String,java.lang.String)', }, { p: 'com.technototes.library.control', c: 'ButtonBase', l: 'booleanSupplier' }, { p: 'com.technototes.library.hardware.motor', c: 'EncodedMotor', l: 'brake()' }, @@ -183,8 +177,6 @@ memberSearchIndex = [ l: 'ChoiceCommand(Pair...)', u: '%3Cinit%3E(android.util.Pair...)', }, - { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'circle' }, - { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'CIRCLE' }, { p: 'com.technototes.library.command', c: 'Command', l: 'clear()' }, { p: 'com.technototes.library.hardware', c: 'DummyDevice', l: 'close()' }, { @@ -203,12 +195,6 @@ memberSearchIndex = [ { p: 'com.technototes.library.hardware.motor', c: 'Motor', l: 'coast()' }, { p: 'com.technototes.library.hardware2', c: 'MotorBuilder', l: 'coast()' }, { p: 'com.technototes.library.structure', c: 'CommandOpMode', l: 'codriverGamepad' }, - { p: 'com.technototes.library.logger.entry', c: 'Entry', l: 'color' }, - { p: 'com.technototes.library.logger', c: 'Log.Boolean', l: 'color()' }, - { p: 'com.technototes.library.logger', c: 'Log', l: 'color()' }, - { p: 'com.technototes.library.logger', c: 'Log.Number', l: 'color()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberBar', l: 'color()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberSlider', l: 'color()' }, { p: 'com.technototes.library.hardware2', c: 'HardwareBuilder', @@ -319,7 +305,6 @@ memberSearchIndex = [ l: 'CommandOpMode()', u: '%3Cinit%3E()', }, - { p: 'com.technototes.library.logger', c: 'Log.NumberBar', l: 'completeBarColor()' }, { p: 'com.technototes.library.command', c: 'ConditionalCommand', @@ -372,8 +357,6 @@ memberSearchIndex = [ l: 'create(String)', u: 'create(java.lang.String)', }, - { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'cross' }, - { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'CROSS' }, { p: 'com.technototes.library.hardware2', c: 'HardwareBuilder', l: 'crServo(int)' }, { p: 'com.technototes.library.hardware2', @@ -603,10 +586,9 @@ memberSearchIndex = [ { p: 'com.technototes.library.logger.entry', c: 'Entry', - l: 'Entry(String, Supplier, int, Color)', - u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int,com.technototes.library.util.Color)', + l: 'Entry(String, Supplier, int)', + u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int)', }, - { p: 'com.technototes.library.logger', c: 'Log', l: 'entryColor()' }, { p: 'com.technototes.library.command', c: 'Command', l: 'execute()' }, { p: 'com.technototes.library.command', c: 'CommandBase', l: 'execute()' }, { p: 'com.technototes.library.command', c: 'CommandGroup', l: 'execute()' }, @@ -627,8 +609,6 @@ memberSearchIndex = [ l: 'ExternalEncoder(String)', u: '%3Cinit%3E(java.lang.String)', }, - { p: 'com.technototes.library.logger', c: 'Log.Boolean', l: 'falseColor()' }, - { p: 'com.technototes.library.logger', c: 'Log.Boolean', l: 'falseFormat()' }, { p: 'com.technototes.library.logger', c: 'Log.Boolean', l: 'falseValue()' }, { p: 'com.technototes.library.command', c: 'Command.CommandState', l: 'FINISHED' }, { @@ -814,7 +794,6 @@ memberSearchIndex = [ u: 'getDistance(org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit)', }, { p: 'com.technototes.library.control', c: 'Stick', l: 'getDistanceFromCenter()' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'getDouble()' }, { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'getDpad()' }, { p: 'com.technototes.library.hardware.motor', c: 'EncodedMotor', l: 'getEncoder()' }, { p: 'com.technototes.library.hardware', c: 'HardwareDeviceGroup', l: 'getFollowerist()' }, @@ -908,7 +887,6 @@ memberSearchIndex = [ { p: 'com.technototes.library.command', c: 'Command', l: 'getState()' }, { p: 'com.technototes.library.control', c: 'Binding', l: 'getSuppliers()' }, { p: 'com.technototes.library.control', c: 'CommandBinding', l: 'getSuppliers()' }, - { p: 'com.technototes.library.logger.entry', c: 'Entry', l: 'getTag()' }, { p: 'com.technototes.library.hardware.servo', c: 'ServoProfiler', l: 'getTargetPosition()' }, { p: 'com.technototes.library.hardware.servo', c: 'ServoProfiler', l: 'getTargetTolerance()' }, { p: 'com.technototes.library.control', c: 'AxisBase', l: 'getTriggerThreshold()' }, @@ -1028,13 +1006,10 @@ memberSearchIndex = [ l: 'IMUBuilder(String)', u: '%3Cinit%3E(java.lang.String)', }, - { p: 'com.technototes.library.logger', c: 'Log.NumberBar', l: 'incompleteBarColor()' }, { p: 'com.technototes.library.hardware.servo', c: 'Servo', l: 'incrementPosition(double)' }, { p: 'com.technototes.library.logger', c: 'Log.Boolean', l: 'index()' }, { p: 'com.technototes.library.logger', c: 'Log', l: 'index()' }, { p: 'com.technototes.library.logger', c: 'Log.Number', l: 'index()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberBar', l: 'index()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberSlider', l: 'index()' }, { p: 'com.technototes.library.structure', c: 'CommandOpMode.OpModeState', l: 'INIT' }, { p: 'com.technototes.library.logger', c: 'Logger', l: 'initEntries' }, { p: 'com.technototes.library.command', c: 'Command', l: 'initialize()' }, @@ -1182,11 +1157,7 @@ memberSearchIndex = [ }, { p: 'com.technototes.library.util', c: 'MapUtils', l: 'MapUtils()', u: '%3Cinit%3E()' }, { p: 'com.technototes.library.util', c: 'MathUtils', l: 'MathUtils()', u: '%3Cinit%3E()' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'max' }, { p: 'com.technototes.library.util', c: 'Range', l: 'max' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'max()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberBar', l: 'max()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberSlider', l: 'max()' }, { p: 'com.technototes.library.hardware.servo', c: 'ServoProfiler.Constraints', @@ -1195,11 +1166,7 @@ memberSearchIndex = [ { p: 'com.technototes.library.subsystem.motor', c: 'EncodedMotorSubsystem', l: 'maxSpeed' }, { p: 'com.technototes.library.hardware.servo', c: 'ServoProfiler.Constraints', l: 'maxVelocity' }, { p: 'com.technototes.library.util', c: 'Range', l: 'middle()' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'min' }, { p: 'com.technototes.library.util', c: 'Range', l: 'min' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'min()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberBar', l: 'min()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberSlider', l: 'min()' }, { p: 'com.technototes.library.hardware2', c: 'MotorBuilder', @@ -1290,8 +1257,6 @@ memberSearchIndex = [ { p: 'com.technototes.library.logger', c: 'Log.Boolean', l: 'name()' }, { p: 'com.technototes.library.logger', c: 'Log', l: 'name()' }, { p: 'com.technototes.library.logger', c: 'Log.Number', l: 'name()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberBar', l: 'name()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberSlider', l: 'name()' }, { p: 'com.technototes.library.util', c: 'Differential.DifferentialPriority', l: 'NEUTRAL' }, { p: 'com.technototes.library.hardware.sensor', c: 'IMU.AxesSigns', l: 'NNN' }, { p: 'com.technototes.library.hardware2', c: 'IMUBuilder.AxesSigns', l: 'NNN' }, @@ -1304,31 +1269,12 @@ memberSearchIndex = [ { p: 'com.technototes.library.hardware2', c: 'IMUBuilder.AxesSigns', l: 'NPN' }, { p: 'com.technototes.library.hardware.sensor', c: 'IMU.AxesSigns', l: 'NPP' }, { p: 'com.technototes.library.hardware2', c: 'IMUBuilder.AxesSigns', l: 'NPP' }, - { - p: 'com.technototes.library.logger.entry', - c: 'NumberBarEntry', - l: 'NumberBarEntry(String, Supplier, int, Number, Number, Number, Color, Color, Color, Color)', - u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int,java.lang.Number,java.lang.Number,java.lang.Number,com.technototes.library.util.Color,com.technototes.library.util.Color,com.technototes.library.util.Color,com.technototes.library.util.Color)', - }, { p: 'com.technototes.library.logger.entry', c: 'NumberEntry', l: 'numberColor' }, - { p: 'com.technototes.library.logger', c: 'Log.Number', l: 'numberColor()' }, - { - p: 'com.technototes.library.logger.entry', - c: 'NumberEntry', - l: 'NumberEntry(String, Supplier, int, Color)', - u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int,com.technototes.library.util.Color)', - }, { p: 'com.technototes.library.logger.entry', c: 'NumberEntry', - l: 'NumberEntry(String, Supplier, int, Color, Color)', - u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int,com.technototes.library.util.Color,com.technototes.library.util.Color)', - }, - { - p: 'com.technototes.library.logger.entry', - c: 'NumberSliderEntry', - l: 'NumberSliderEntry(String, Supplier, int, Number, Number, Number, Color, Color, Color, Color)', - u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int,java.lang.Number,java.lang.Number,java.lang.Number,com.technototes.library.util.Color,com.technototes.library.util.Color,com.technototes.library.util.Color,com.technototes.library.util.Color)', + l: 'NumberEntry(String, Supplier, int)', + u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int)', }, { p: 'com.technototes.library.util', @@ -1368,11 +1314,7 @@ memberSearchIndex = [ l: 'onUnit(DistanceUnit)', u: 'onUnit(org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit)', }, - { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'options' }, - { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'OPTIONS' }, { p: 'com.technototes.library.util', c: 'Color', l: 'ORANGE' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberBar', l: 'outline()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberSlider', l: 'outline()' }, { p: 'com.technototes.library.hardware2', c: 'DigitalBuilder', l: 'output()' }, { p: 'com.technototes.library.command', @@ -1416,12 +1358,9 @@ memberSearchIndex = [ { p: 'com.technototes.library.hardware2', c: 'IMUBuilder.AxesSigns', l: 'PPN' }, { p: 'com.technototes.library.hardware.sensor', c: 'IMU.AxesSigns', l: 'PPP' }, { p: 'com.technototes.library.hardware2', c: 'IMUBuilder.AxesSigns', l: 'PPP' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'primary' }, { p: 'com.technototes.library.logger.entry', c: 'Entry', l: 'priority' }, { p: 'com.technototes.library.logger', c: 'Log.Boolean', l: 'priority()' }, { p: 'com.technototes.library.logger', c: 'Log.Number', l: 'priority()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberBar', l: 'priority()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberSlider', l: 'priority()' }, { p: 'com.technototes.library.logger', c: 'Log', l: 'priority()' }, { p: 'com.technototes.library.hardware2', c: 'HardwareBuilder', l: 'product' }, { p: 'com.technototes.library.hardware', c: 'HardwareDeviceGroup', l: 'propagate(double)' }, @@ -1430,6 +1369,18 @@ memberSearchIndex = [ { p: 'com.technototes.library.hardware.motor', c: 'MotorGroup', l: 'propogate(double)' }, { p: 'com.technototes.library.hardware.servo', c: 'ServoGroup', l: 'propogate(double)' }, { p: 'com.technototes.library.hardware.servo', c: 'ServoProfiler.Constraints', l: 'proportion' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'ps_circle' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'PS_CIRCLE' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'ps_cross' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'PS_CROSS' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'ps_options' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'PS_OPTIONS' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'ps_share' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'PS_SHARE' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'ps_square' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'PS_SQUARE' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'ps_triangle' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'PS_TRIANGLE' }, { p: 'com.technototes.library.util', c: 'Color', l: 'PURPLE' }, { p: 'com.technototes.library.hardware2', @@ -1561,10 +1512,6 @@ memberSearchIndex = [ { p: 'com.technototes.library.structure', c: 'CommandOpMode', l: 'runOpMode()' }, { p: 'com.technototes.library.logger', c: 'Logger', l: 'runUpdate()' }, { p: 'com.technototes.library.hardware.sensor', c: 'IColorSensor', l: 'saturation()' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'scale' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'scale()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberBar', l: 'scale()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberSlider', l: 'scale()' }, { p: 'com.technototes.library.util', c: 'Range', l: 'scale(double)' }, { p: 'com.technototes.library.hardware.servo', @@ -1776,7 +1723,6 @@ memberSearchIndex = [ l: 'scheduleWithOther(Command, Command, BooleanSupplier)', u: 'scheduleWithOther(com.technototes.library.command.Command,com.technototes.library.command.Command,java.util.function.BooleanSupplier)', }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'secondary' }, { p: 'com.technototes.library.util', c: 'Alliance.Selector', @@ -2031,8 +1977,6 @@ memberSearchIndex = [ { p: 'com.technototes.library.hardware.motor', c: 'EncodedMotor', l: 'setVelocity(double)' }, { p: 'com.technototes.library.hardware.motor', c: 'EncodedMotorGroup', l: 'setVelocity(double)' }, { p: 'com.technototes.library.hardware', c: 'Speaker', l: 'setVolume(float)' }, - { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'share' }, - { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'SHARE' }, { p: 'com.technototes.library.subsystem.drivebase', c: 'SimpleMecanumDrivebaseSubsystem', @@ -2052,8 +1996,6 @@ memberSearchIndex = [ l: 'sleep(DoubleSupplier)', u: 'sleep(java.util.function.DoubleSupplier)', }, - { p: 'com.technototes.library.logger', c: 'Log.NumberSlider', l: 'slider()' }, - { p: 'com.technototes.library.logger', c: 'Log.NumberSlider', l: 'sliderBackground()' }, { p: 'com.technototes.library.control', c: 'Binding.Type', l: 'SOME_ACTIVE' }, { p: 'com.technototes.library.hardware', @@ -2067,10 +2009,6 @@ memberSearchIndex = [ l: 'Speaker(String...)', u: '%3Cinit%3E(java.lang.String...)', }, - { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'square' }, - { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'SQUARE' }, - { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'start' }, - { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'START' }, { p: 'com.technototes.library.hardware', c: 'Speaker', @@ -2094,11 +2032,10 @@ memberSearchIndex = [ { p: 'com.technototes.library.logger.entry', c: 'StringEntry', - l: 'StringEntry(String, Supplier, int, Color, String, Color)', - u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int,com.technototes.library.util.Color,java.lang.String,com.technototes.library.util.Color)', + l: 'StringEntry(String, Supplier, int, String)', + u: '%3Cinit%3E(java.lang.String,java.util.function.Supplier,int,java.lang.String)', }, { p: 'com.technototes.library.logger.entry', c: 'Entry', l: 'supplier' }, - { p: 'com.technototes.library.logger.entry', c: 'Entry', l: 'tag' }, { p: 'com.technototes.library.subsystem.drivebase', c: 'TankDrivebaseSubsystem', @@ -2110,7 +2047,6 @@ memberSearchIndex = [ { p: 'com.qualcomm.robotcore.eventloop.opmode', c: 'CommandOpMode', l: 'telemetry' }, { p: 'com.technototes.library.structure', c: 'CommandOpMode', l: 'terminate()' }, { p: 'com.technototes.library.command', c: 'CommandScheduler', l: 'terminateOpMode()' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'tertiary' }, { p: 'com.technototes.library.command', c: 'Command', l: 'timeMap' }, { p: 'com.technototes.library.control', @@ -2122,19 +2058,13 @@ memberSearchIndex = [ { p: 'com.technototes.library.hardware2', c: 'MotorBuilder', l: 'tolerance(int)' }, { p: 'com.technototes.library.logger.entry', c: 'BooleanEntry', l: 'toString()' }, { p: 'com.technototes.library.logger.entry', c: 'Entry', l: 'toString()' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberBarEntry', l: 'toString()' }, { p: 'com.technototes.library.logger.entry', c: 'NumberEntry', l: 'toString()' }, - { p: 'com.technototes.library.logger.entry', c: 'NumberSliderEntry', l: 'toString()' }, { p: 'com.technototes.library.logger.entry', c: 'StringEntry', l: 'toString()' }, { p: 'com.technototes.library.hardware.servo', c: 'ServoProfiler', l: 'translateTargetPosition(double)', }, - { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'triangle' }, - { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'TRIANGLE' }, - { p: 'com.technototes.library.logger', c: 'Log.Boolean', l: 'trueColor()' }, - { p: 'com.technototes.library.logger', c: 'Log.Boolean', l: 'trueFormat()' }, { p: 'com.technototes.library.logger', c: 'Log.Boolean', l: 'trueValue()' }, { p: 'com.technototes.library.structure', c: 'CommandOpMode', l: 'universalLoop()' }, { p: 'com.technototes.library.control', c: 'GamepadDpad', l: 'up' }, @@ -2144,8 +2074,8 @@ memberSearchIndex = [ { p: 'com.technototes.library.structure', c: 'CommandOpMode', l: 'uponStart()' }, { p: 'com.technototes.library.hardware.sensor', c: 'IColorSensor', l: 'value()' }, { p: 'com.technototes.library.logger', c: 'Log.Logs', l: 'value()' }, - { p: 'com.technototes.library.logger', c: 'LogConfig.Blacklist', l: 'value()' }, - { p: 'com.technototes.library.logger', c: 'LogConfig.Whitelist', l: 'value()' }, + { p: 'com.technototes.library.logger', c: 'LogConfig.AllowList', l: 'value()' }, + { p: 'com.technototes.library.logger', c: 'LogConfig.DenyList', l: 'value()' }, { p: 'com.technototes.library.command', c: 'Command.CommandState', @@ -2331,12 +2261,20 @@ memberSearchIndex = [ }, { p: 'com.technototes.library.util', c: 'Color', l: 'WHITE' }, { p: 'com.technototes.library.command', c: 'Command', l: 'withTimeout(double)' }, - { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'x' }, { p: 'com.technototes.library.logger.entry', c: 'Entry', l: 'x' }, - { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'X' }, { p: 'com.technototes.library.control', c: 'GamepadStick', l: 'xAxis' }, - { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'y' }, - { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'Y' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'xbox_a' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'XBOX_A' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'xbox_b' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'XBOX_B' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'xbox_back' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'XBOX_BACK' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'xbox_start' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'XBOX_START' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'xbox_x' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'XBOX_X' }, + { p: 'com.technototes.library.control', c: 'GamepadBase', l: 'xbox_y' }, + { p: 'com.technototes.library.control', c: 'GamepadBase.Button', l: 'XBOX_Y' }, { p: 'com.technototes.library.control', c: 'GamepadStick', l: 'yAxis' }, { p: 'com.technototes.library.util', c: 'Color', l: 'YELLOW' }, { p: 'com.technototes.library.hardware.sensor', c: 'IGyro', l: 'zero()' }, diff --git a/docs/TechnoLib/overview-tree.html b/docs/TechnoLib/overview-tree.html index b7bc433e..39c56ae2 100644 --- a/docs/TechnoLib/overview-tree.html +++ b/docs/TechnoLib/overview-tree.html @@ -474,26 +474,6 @@

    Class Hierarchy

    title="class in com.technototes.library.logger.entry" >NumberEntry
    -
  • com.technototes.library.logger.entry.Annotation Interface Hierarchy
  • com.technototes.library.logger.Log.NumberBar - (implements java.lang.annotation.Annotation) -
  • -
  • - com.technototes.library.logger.Log.NumberSliderLogConfig (implements java.lang.annotation.Annotation Interface Hierarchy
  • com.technototes.library.logger.LogConfigLogConfig.AllowList (implements java.lang.annotation.Annotation Interface Hierarchy
  • com.technototes.library.logger.LogConfig.BlacklistLogConfig.DenyList (implements java.lang.annotation.Annotation Interface Hierarchy >Annotation)
  • -
  • - com.technototes.library.logger.LogConfig.Whitelist - (implements java.lang.annotation.Annotation) -
  • diff --git a/docs/TechnoLib/src-html/com/technototes/library/control/CommandAxis.html b/docs/TechnoLib/src-html/com/technototes/library/control/CommandAxis.html index afe55554..91a383bd 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/control/CommandAxis.html +++ b/docs/TechnoLib/src-html/com/technototes/library/control/CommandAxis.html @@ -17,60 +17,64 @@ 004import java.util.function.DoubleSupplier; 005import java.util.function.Function; 006 -007/** Class for command axis for the gamepad -008 * @author Alex Stedman -009 */ -010public class CommandAxis extends AxisBase implements CommandInput<CommandAxis> { -011 -012 /** Make a command axis -013 * -014 * @param supplier The axis supplier -015 */ -016 public CommandAxis(DoubleSupplier supplier) { -017 super(supplier); -018 } -019 -020 /** Make a command axis -021 * -022 * @param supplier The axis supplier -023 * @param threshold The threshold to trigger to make the axis behave as a button -024 */ -025 public CommandAxis(DoubleSupplier supplier, double threshold) { -026 super(supplier, threshold); -027 } -028 -029 @Override -030 public CommandAxis getInstance() { -031 return this; -032 } -033 -034 @Override -035 public CommandAxis setTriggerThreshold(double threshold) { -036 super.setTriggerThreshold(threshold); -037 return this; -038 } -039 -040 public CommandAxis schedulePressed(Function<DoubleSupplier, Command> f) { -041 return whilePressed(f.apply(this)); +007/** +008 * Class for command axis for the gamepad +009 * +010 * @author Alex Stedman +011 */ +012public class CommandAxis extends AxisBase implements CommandInput<CommandAxis> { +013 +014 /** +015 * Make a command axis +016 * +017 * @param supplier The axis supplier +018 */ +019 public CommandAxis(DoubleSupplier supplier) { +020 super(supplier); +021 } +022 +023 /** +024 * Make a command axis +025 * +026 * @param supplier The axis supplier +027 * @param threshold The threshold to trigger to make the axis behave as a button +028 */ +029 public CommandAxis(DoubleSupplier supplier, double threshold) { +030 super(supplier, threshold); +031 } +032 +033 @Override +034 public CommandAxis getInstance() { +035 return this; +036 } +037 +038 @Override +039 public CommandAxis setTriggerThreshold(double threshold) { +040 super.setTriggerThreshold(threshold); +041 return this; 042 } 043 -044 public CommandAxis schedule(Function<Double, Command> f) { -045 return schedule(f.apply(this.getAsDouble())); +044 public CommandAxis schedulePressed(Function<DoubleSupplier, Command> f) { +045 return whilePressed(f.apply(this)); 046 } 047 -048 @Override -049 public CommandAxis setInverted(boolean invert) { -050 return (CommandAxis) super.setInverted(invert); -051 } -052 -053 public CommandButton getAsButton() { -054 return new CommandButton(this); +048 public CommandAxis schedule(Function<Double, Command> f) { +049 return schedule(f.apply(this.getAsDouble())); +050 } +051 +052 @Override +053 public CommandAxis setInverted(boolean invert) { +054 return (CommandAxis) super.setInverted(invert); 055 } 056 -057 public CommandButton getAsButton(double threshold) { -058 return new CommandButton(() -> threshold >= 0 ? getAsDouble() >= threshold : getAsDouble() < threshold); +057 public CommandButton getAsButton() { +058 return new CommandButton(this); 059 } -060} +060 +061 public CommandButton getAsButton(double threshold) { +062 return new CommandButton(() -> (threshold >= 0) ? (getAsDouble() >= threshold) : (getAsDouble() < threshold)); +063 } +064} diff --git a/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.Axis.html b/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.Axis.html index db72be3c..397bb4eb 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.Axis.html +++ b/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.Axis.html @@ -35,11 +35,11 @@ 022 /** 023 * The button objects for the XBox game controller 024 */ -025 public T a, b, x, y, start, back; +025 public T xbox_a, xbox_b, xbox_x, xbox_y, xbox_start, xbox_back; 026 /** 027 * The button objects for the PS4 game controller 028 */ -029 public T cross, circle, square, triangle, share, options; +029 public T ps_cross, ps_circle, ps_square, ps_triangle, ps_share, ps_options; 030 /** 031 * The button objects for both the XBox and PS4 controllers 032 */ @@ -86,12 +86,12 @@ 073 dpad = new GamepadDpad<>(dpadUp, dpadDown, dpadLeft, dpadRight); 074 periodics = 075 new Periodic[] { -076 a, -077 b, -078 x, -079 y, -080 start, -081 back, +076 xbox_a, +077 xbox_b, +078 xbox_x, +079 xbox_y, +080 xbox_start, +081 xbox_back, 082 leftBumper, 083 rightBumper, 084 leftTrigger, @@ -102,12 +102,12 @@ 089 }; 090 enablables = 091 new Enablable[] { -092 a, -093 b, -094 x, -095 y, -096 start, -097 back, +092 xbox_a, +093 xbox_b, +094 xbox_x, +095 xbox_y, +096 xbox_start, +097 xbox_back, 098 leftBumper, 099 rightBumper, 100 leftTrigger, @@ -123,19 +123,19 @@ 110 throws InstantiationException, IllegalAccessException, NoSuchMethodException, InvocationTargetException { 111 // buttons 112 // a=new T(); -113 a = buttonInstance(() -> g.a); -114 b = buttonInstance(() -> g.b); -115 x = buttonInstance(() -> g.x); -116 y = buttonInstance(() -> g.y); -117 cross = a; -118 circle = b; -119 square = x; -120 triangle = y; +113 xbox_a = buttonInstance(() -> g.a); +114 xbox_b = buttonInstance(() -> g.b); +115 xbox_x = buttonInstance(() -> g.x); +116 xbox_y = buttonInstance(() -> g.y); +117 ps_cross = xbox_a; +118 ps_circle = xbox_b; +119 ps_square = xbox_x; +120 ps_triangle = xbox_y; 121 -122 start = buttonInstance(() -> g.start); -123 back = buttonInstance(() -> g.back); -124 share = back; -125 options = start; +122 xbox_start = buttonInstance(() -> g.start); +123 xbox_back = buttonInstance(() -> g.back); +124 ps_share = xbox_back; +125 ps_options = xbox_start; 126 127 // bumpers 128 leftBumper = buttonInstance(() -> g.left_bumper); @@ -171,51 +171,51 @@ 158 /** 159 * XBox A button 160 */ -161 A, +161 XBOX_A, 162 /** 163 * XBox B button 164 */ -165 B, +165 XBOX_B, 166 /** 167 * XBox X button 168 */ -169 X, +169 XBOX_X, 170 /** 171 * XBox Y button 172 */ -173 Y, +173 XBOX_Y, 174 /** 175 * PS4 Cross (X) button 176 */ -177 CROSS, +177 PS_CROSS, 178 /** 179 * PS4 Circle (O) button 180 */ -181 CIRCLE, +181 PS_CIRCLE, 182 /** 183 * PS4 Square button 184 */ -185 SQUARE, +185 PS_SQUARE, 186 /** 187 * PS4 Triangle button 188 */ -189 TRIANGLE, +189 PS_TRIANGLE, 190 /** 191 * PS4 Share button 192 */ -193 SHARE, +193 PS_SHARE, 194 /** 195 * PS4 Options button 196 */ -197 OPTIONS, +197 PS_OPTIONS, 198 /** -199 * PS4/XBox Start button +199 * XBox Start button 200 */ -201 START, +201 XBOX_START, 202 /** -203 * PS4/XBox Back button +203 * XBox Back button 204 */ -205 BACK, +205 XBOX_BACK, 206 /** 207 * Left bumper button 208 */ @@ -272,30 +272,30 @@ 259 */ 260 public T getButton(Button bu) { 261 switch (bu) { -262 case A: -263 return a; -264 case B: -265 return b; -266 case X: -267 return x; -268 case Y: -269 return y; -270 case CROSS: -271 return cross; -272 case CIRCLE: -273 return circle; -274 case SQUARE: -275 return square; -276 case TRIANGLE: -277 return triangle; -278 case SHARE: -279 return share; -280 case OPTIONS: -281 return options; -282 case BACK: -283 return back; -284 case START: -285 return start; +262 case XBOX_A: +263 return xbox_a; +264 case XBOX_B: +265 return xbox_b; +266 case XBOX_X: +267 return xbox_x; +268 case XBOX_Y: +269 return xbox_y; +270 case PS_CROSS: +271 return ps_cross; +272 case PS_CIRCLE: +273 return ps_circle; +274 case PS_SQUARE: +275 return ps_square; +276 case PS_TRIANGLE: +277 return ps_triangle; +278 case PS_SHARE: +279 return ps_share; +280 case PS_OPTIONS: +281 return ps_options; +282 case XBOX_BACK: +283 return xbox_back; +284 case XBOX_START: +285 return xbox_start; 286 case LEFT_BUMPER: 287 return leftBumper; 288 case RIGHT_BUMPER: diff --git a/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.Button.html b/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.Button.html index f96b066f..82cb5878 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.Button.html +++ b/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.Button.html @@ -35,11 +35,11 @@ 022 /** 023 * The button objects for the XBox game controller 024 */ -025 public T a, b, x, y, start, back; +025 public T xbox_a, xbox_b, xbox_x, xbox_y, xbox_start, xbox_back; 026 /** 027 * The button objects for the PS4 game controller 028 */ -029 public T cross, circle, square, triangle, share, options; +029 public T ps_cross, ps_circle, ps_square, ps_triangle, ps_share, ps_options; 030 /** 031 * The button objects for both the XBox and PS4 controllers 032 */ @@ -86,12 +86,12 @@ 073 dpad = new GamepadDpad<>(dpadUp, dpadDown, dpadLeft, dpadRight); 074 periodics = 075 new Periodic[] { -076 a, -077 b, -078 x, -079 y, -080 start, -081 back, +076 xbox_a, +077 xbox_b, +078 xbox_x, +079 xbox_y, +080 xbox_start, +081 xbox_back, 082 leftBumper, 083 rightBumper, 084 leftTrigger, @@ -102,12 +102,12 @@ 089 }; 090 enablables = 091 new Enablable[] { -092 a, -093 b, -094 x, -095 y, -096 start, -097 back, +092 xbox_a, +093 xbox_b, +094 xbox_x, +095 xbox_y, +096 xbox_start, +097 xbox_back, 098 leftBumper, 099 rightBumper, 100 leftTrigger, @@ -123,19 +123,19 @@ 110 throws InstantiationException, IllegalAccessException, NoSuchMethodException, InvocationTargetException { 111 // buttons 112 // a=new T(); -113 a = buttonInstance(() -> g.a); -114 b = buttonInstance(() -> g.b); -115 x = buttonInstance(() -> g.x); -116 y = buttonInstance(() -> g.y); -117 cross = a; -118 circle = b; -119 square = x; -120 triangle = y; +113 xbox_a = buttonInstance(() -> g.a); +114 xbox_b = buttonInstance(() -> g.b); +115 xbox_x = buttonInstance(() -> g.x); +116 xbox_y = buttonInstance(() -> g.y); +117 ps_cross = xbox_a; +118 ps_circle = xbox_b; +119 ps_square = xbox_x; +120 ps_triangle = xbox_y; 121 -122 start = buttonInstance(() -> g.start); -123 back = buttonInstance(() -> g.back); -124 share = back; -125 options = start; +122 xbox_start = buttonInstance(() -> g.start); +123 xbox_back = buttonInstance(() -> g.back); +124 ps_share = xbox_back; +125 ps_options = xbox_start; 126 127 // bumpers 128 leftBumper = buttonInstance(() -> g.left_bumper); @@ -171,51 +171,51 @@ 158 /** 159 * XBox A button 160 */ -161 A, +161 XBOX_A, 162 /** 163 * XBox B button 164 */ -165 B, +165 XBOX_B, 166 /** 167 * XBox X button 168 */ -169 X, +169 XBOX_X, 170 /** 171 * XBox Y button 172 */ -173 Y, +173 XBOX_Y, 174 /** 175 * PS4 Cross (X) button 176 */ -177 CROSS, +177 PS_CROSS, 178 /** 179 * PS4 Circle (O) button 180 */ -181 CIRCLE, +181 PS_CIRCLE, 182 /** 183 * PS4 Square button 184 */ -185 SQUARE, +185 PS_SQUARE, 186 /** 187 * PS4 Triangle button 188 */ -189 TRIANGLE, +189 PS_TRIANGLE, 190 /** 191 * PS4 Share button 192 */ -193 SHARE, +193 PS_SHARE, 194 /** 195 * PS4 Options button 196 */ -197 OPTIONS, +197 PS_OPTIONS, 198 /** -199 * PS4/XBox Start button +199 * XBox Start button 200 */ -201 START, +201 XBOX_START, 202 /** -203 * PS4/XBox Back button +203 * XBox Back button 204 */ -205 BACK, +205 XBOX_BACK, 206 /** 207 * Left bumper button 208 */ @@ -272,30 +272,30 @@ 259 */ 260 public T getButton(Button bu) { 261 switch (bu) { -262 case A: -263 return a; -264 case B: -265 return b; -266 case X: -267 return x; -268 case Y: -269 return y; -270 case CROSS: -271 return cross; -272 case CIRCLE: -273 return circle; -274 case SQUARE: -275 return square; -276 case TRIANGLE: -277 return triangle; -278 case SHARE: -279 return share; -280 case OPTIONS: -281 return options; -282 case BACK: -283 return back; -284 case START: -285 return start; +262 case XBOX_A: +263 return xbox_a; +264 case XBOX_B: +265 return xbox_b; +266 case XBOX_X: +267 return xbox_x; +268 case XBOX_Y: +269 return xbox_y; +270 case PS_CROSS: +271 return ps_cross; +272 case PS_CIRCLE: +273 return ps_circle; +274 case PS_SQUARE: +275 return ps_square; +276 case PS_TRIANGLE: +277 return ps_triangle; +278 case PS_SHARE: +279 return ps_share; +280 case PS_OPTIONS: +281 return ps_options; +282 case XBOX_BACK: +283 return xbox_back; +284 case XBOX_START: +285 return xbox_start; 286 case LEFT_BUMPER: 287 return leftBumper; 288 case RIGHT_BUMPER: diff --git a/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.html b/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.html index ffbe3209..7a387cb3 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.html +++ b/docs/TechnoLib/src-html/com/technototes/library/control/GamepadBase.html @@ -35,11 +35,11 @@ 022 /** 023 * The button objects for the XBox game controller 024 */ -025 public T a, b, x, y, start, back; +025 public T xbox_a, xbox_b, xbox_x, xbox_y, xbox_start, xbox_back; 026 /** 027 * The button objects for the PS4 game controller 028 */ -029 public T cross, circle, square, triangle, share, options; +029 public T ps_cross, ps_circle, ps_square, ps_triangle, ps_share, ps_options; 030 /** 031 * The button objects for both the XBox and PS4 controllers 032 */ @@ -86,12 +86,12 @@ 073 dpad = new GamepadDpad<>(dpadUp, dpadDown, dpadLeft, dpadRight); 074 periodics = 075 new Periodic[] { -076 a, -077 b, -078 x, -079 y, -080 start, -081 back, +076 xbox_a, +077 xbox_b, +078 xbox_x, +079 xbox_y, +080 xbox_start, +081 xbox_back, 082 leftBumper, 083 rightBumper, 084 leftTrigger, @@ -102,12 +102,12 @@ 089 }; 090 enablables = 091 new Enablable[] { -092 a, -093 b, -094 x, -095 y, -096 start, -097 back, +092 xbox_a, +093 xbox_b, +094 xbox_x, +095 xbox_y, +096 xbox_start, +097 xbox_back, 098 leftBumper, 099 rightBumper, 100 leftTrigger, @@ -123,19 +123,19 @@ 110 throws InstantiationException, IllegalAccessException, NoSuchMethodException, InvocationTargetException { 111 // buttons 112 // a=new T(); -113 a = buttonInstance(() -> g.a); -114 b = buttonInstance(() -> g.b); -115 x = buttonInstance(() -> g.x); -116 y = buttonInstance(() -> g.y); -117 cross = a; -118 circle = b; -119 square = x; -120 triangle = y; +113 xbox_a = buttonInstance(() -> g.a); +114 xbox_b = buttonInstance(() -> g.b); +115 xbox_x = buttonInstance(() -> g.x); +116 xbox_y = buttonInstance(() -> g.y); +117 ps_cross = xbox_a; +118 ps_circle = xbox_b; +119 ps_square = xbox_x; +120 ps_triangle = xbox_y; 121 -122 start = buttonInstance(() -> g.start); -123 back = buttonInstance(() -> g.back); -124 share = back; -125 options = start; +122 xbox_start = buttonInstance(() -> g.start); +123 xbox_back = buttonInstance(() -> g.back); +124 ps_share = xbox_back; +125 ps_options = xbox_start; 126 127 // bumpers 128 leftBumper = buttonInstance(() -> g.left_bumper); @@ -171,51 +171,51 @@ 158 /** 159 * XBox A button 160 */ -161 A, +161 XBOX_A, 162 /** 163 * XBox B button 164 */ -165 B, +165 XBOX_B, 166 /** 167 * XBox X button 168 */ -169 X, +169 XBOX_X, 170 /** 171 * XBox Y button 172 */ -173 Y, +173 XBOX_Y, 174 /** 175 * PS4 Cross (X) button 176 */ -177 CROSS, +177 PS_CROSS, 178 /** 179 * PS4 Circle (O) button 180 */ -181 CIRCLE, +181 PS_CIRCLE, 182 /** 183 * PS4 Square button 184 */ -185 SQUARE, +185 PS_SQUARE, 186 /** 187 * PS4 Triangle button 188 */ -189 TRIANGLE, +189 PS_TRIANGLE, 190 /** 191 * PS4 Share button 192 */ -193 SHARE, +193 PS_SHARE, 194 /** 195 * PS4 Options button 196 */ -197 OPTIONS, +197 PS_OPTIONS, 198 /** -199 * PS4/XBox Start button +199 * XBox Start button 200 */ -201 START, +201 XBOX_START, 202 /** -203 * PS4/XBox Back button +203 * XBox Back button 204 */ -205 BACK, +205 XBOX_BACK, 206 /** 207 * Left bumper button 208 */ @@ -272,30 +272,30 @@ 259 */ 260 public T getButton(Button bu) { 261 switch (bu) { -262 case A: -263 return a; -264 case B: -265 return b; -266 case X: -267 return x; -268 case Y: -269 return y; -270 case CROSS: -271 return cross; -272 case CIRCLE: -273 return circle; -274 case SQUARE: -275 return square; -276 case TRIANGLE: -277 return triangle; -278 case SHARE: -279 return share; -280 case OPTIONS: -281 return options; -282 case BACK: -283 return back; -284 case START: -285 return start; +262 case XBOX_A: +263 return xbox_a; +264 case XBOX_B: +265 return xbox_b; +266 case XBOX_X: +267 return xbox_x; +268 case XBOX_Y: +269 return xbox_y; +270 case PS_CROSS: +271 return ps_cross; +272 case PS_CIRCLE: +273 return ps_circle; +274 case PS_SQUARE: +275 return ps_square; +276 case PS_TRIANGLE: +277 return ps_triangle; +278 case PS_SHARE: +279 return ps_share; +280 case PS_OPTIONS: +281 return ps_options; +282 case XBOX_BACK: +283 return xbox_back; +284 case XBOX_START: +285 return xbox_start; 286 case LEFT_BUMPER: 287 return leftBumper; 288 case RIGHT_BUMPER: diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Boolean.html b/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Boolean.html index 4a9a1d43..f7990aaa 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Boolean.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Boolean.html @@ -17,297 +17,112 @@ 004import static java.lang.annotation.ElementType.LOCAL_VARIABLE; 005import static java.lang.annotation.ElementType.METHOD; 006 -007import com.technototes.library.util.Color; -008import java.lang.annotation.Documented; -009import java.lang.annotation.ElementType; -010import java.lang.annotation.Repeatable; -011import java.lang.annotation.Retention; -012import java.lang.annotation.RetentionPolicy; -013import java.lang.annotation.Target; -014 -015/** The root annotation for annotation logging, also doubles as a basic string log -016 * @author Alex Stedman -017 */ -018@Documented -019@Repeatable(Log.Logs.class) -020@Retention(RetentionPolicy.RUNTIME) -021@Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -022public @interface Log { -023 /** Store index for this annotation (position in telemetry) -024 * -025 * @return The index -026 */ -027 int index() default -1; -028 -029 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -030 * -031 * @return The priority -032 */ -033 int priority() default -1; -034 -035 /** Store the name for this annotation to be be beside -036 * -037 * @return The name as a string -038 */ -039 String name() default ""; -040 -041 /** The format for the logged String -042 * -043 * @return The format -044 */ -045 String format() default "%s"; -046 -047 /** The color for the entry -048 * -049 * @return The color -050 */ -051 Color entryColor() default Color.NO_COLOR; +007import java.lang.annotation.Documented; +008import java.lang.annotation.ElementType; +009import java.lang.annotation.Repeatable; +010import java.lang.annotation.Retention; +011import java.lang.annotation.RetentionPolicy; +012import java.lang.annotation.Target; +013 +014/** The root annotation for annotation logging, also doubles as a basic string log +015 * @author Alex Stedman +016 */ +017@Documented +018@Repeatable(Log.Logs.class) +019@Retention(RetentionPolicy.RUNTIME) +020@Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +021public @interface Log { +022 /** Store index for this annotation (position in telemetry) +023 * +024 * @return The index +025 */ +026 int index() default -1; +027 +028 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +029 * +030 * @return The priority +031 */ +032 int priority() default -1; +033 +034 /** Store the name for this annotation to be be beside +035 * +036 * @return The name as a string +037 */ +038 String name() default ""; +039 +040 /** The format for the logged String +041 * +042 * @return The format +043 */ +044 String format() default "%s"; +045 +046 @Documented +047 @Retention(RetentionPolicy.RUNTIME) +048 @Target({ ElementType.FIELD, ElementType.METHOD }) +049 @interface Logs { +050 Log[] value(); +051 } 052 -053 /** The color for the tag for the entry +053 /** Log a number 054 * -055 * @return The color -056 */ -057 Color color() default Color.NO_COLOR; -058 -059 @Documented -060 @Retention(RetentionPolicy.RUNTIME) -061 @Target({ ElementType.FIELD, ElementType.METHOD }) -062 @interface Logs { -063 Log[] value(); -064 } -065 -066 /** Log a number -067 * -068 */ -069 @Retention(RetentionPolicy.RUNTIME) -070 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -071 @interface Number { -072 /** Store index for this annotation (position in telemetry) -073 * -074 * @return The index -075 */ -076 int index() default -1; +055 */ +056 @Retention(RetentionPolicy.RUNTIME) +057 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +058 @interface Number { +059 /** Store index for this annotation (position in telemetry) +060 * +061 * @return The index +062 */ +063 int index() default -1; +064 +065 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +066 * +067 * @return The priority +068 */ +069 int priority() default -1; +070 +071 /** Store the name for this annotation to be be beside +072 * +073 * @return The name as a string +074 */ +075 String name() default ""; +076 } 077 -078 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -079 * -080 * @return The priority -081 */ -082 int priority() default -1; -083 -084 /** Store the name for this annotation to be be beside -085 * -086 * @return The name as a string -087 */ -088 String name() default ""; -089 -090 /** The color for the tag for the number -091 * -092 * @return The color -093 */ -094 Color color() default Color.NO_COLOR; -095 -096 /** The color for the number -097 * -098 * @return The color -099 */ -100 Color numberColor() default Color.NO_COLOR; -101 } -102 -103 /** Log a number, but store it as a number bar -104 * -105 */ -106 @Retention(RetentionPolicy.RUNTIME) -107 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -108 @interface NumberBar { -109 /** Store index for this annotation (position in telemetry) -110 * -111 * @return The index -112 */ -113 int index() default -1; -114 -115 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -116 * -117 * @return The priority -118 */ -119 int priority() default -1; -120 -121 /** Store the min for the number bar to scale to -122 * -123 * @return The min -124 */ -125 double min() default -1; -126 -127 /** Store the max for the number bar to scale to -128 * -129 * @return The max -130 */ -131 double max() default 1; -132 -133 /** Store the scale for the number bar to scale to -134 * -135 * @return The scale -136 */ -137 double scale() default 0.1; -138 -139 /** Store the name for this annotation to be be beside -140 * -141 * @return The name as a string -142 */ -143 String name() default ""; -144 -145 /** The color for the tag for the bar -146 * -147 * @return The color -148 */ -149 Color color() default Color.NO_COLOR; -150 -151 /** The color for the filled in bar color -152 * -153 * @return The color -154 */ -155 Color completeBarColor() default Color.NO_COLOR; -156 -157 /** The color for the not filled in bar color -158 * -159 * @return The color -160 */ -161 Color incompleteBarColor() default Color.NO_COLOR; -162 -163 /** The color for the bar outlines -164 * -165 * @return The color -166 */ -167 Color outline() default Color.NO_COLOR; -168 } -169 -170 @Retention(RetentionPolicy.RUNTIME) -171 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -172 @interface NumberSlider { -173 /** Store index for this annotation (position in telemetry) -174 * -175 * @return The index -176 */ -177 int index() default -1; -178 -179 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -180 * -181 * @return The priority -182 */ -183 int priority() default -1; -184 -185 /** Store the min for the number bar to scale to -186 * -187 * @return The min -188 */ -189 double min() default -1; -190 -191 /** Store the max for the number bar to scale to -192 * -193 * @return The max -194 */ -195 double max() default 1; -196 -197 /** Store the scale for the number bar to scale to -198 * -199 * @return The scale -200 */ -201 double scale() default 0.1; -202 -203 /** Store the name for this annotation to be be beside -204 * -205 * @return The name as a string -206 */ -207 String name() default ""; -208 -209 /** The color for the tag for the slider -210 * -211 * @return The color -212 */ -213 Color color() default Color.NO_COLOR; -214 -215 /** The color for the slider background -216 * -217 * @return The color -218 */ -219 Color sliderBackground() default Color.NO_COLOR; -220 -221 /** The color for the slider outline -222 * -223 * @return The color -224 */ -225 Color outline() default Color.NO_COLOR; -226 -227 /** The color for the slider slide -228 * -229 * @return The color -230 */ -231 Color slider() default Color.NO_COLOR; -232 } -233 -234 @Retention(RetentionPolicy.RUNTIME) -235 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -236 @interface Boolean { -237 /** Store index for this annotation (position in telemetry) -238 * -239 * @return The index -240 */ -241 int index() default -1; -242 -243 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -244 * -245 * @return The priority -246 */ -247 int priority() default -1; -248 -249 /** Store the string when the annotated method returns true -250 * -251 * @return The string -252 */ -253 String trueValue() default "true"; -254 -255 /** The format for when the boolean returns true -256 * -257 * @return The String format -258 */ -259 String trueFormat() default "%s"; -260 -261 /** The color for the true String -262 * -263 * @return The color -264 */ -265 Color trueColor() default Color.NO_COLOR; -266 -267 /** Store the string when the annotated method returns false -268 * -269 * @return The string -270 */ -271 String falseValue() default "false"; -272 -273 /** The format for when the boolean returns false -274 * -275 * @return The String format -276 */ -277 String falseFormat() default "%s"; -278 -279 /** The color for the false String -280 * -281 * @return The color -282 */ -283 Color falseColor() default Color.NO_COLOR; -284 -285 /** Store the name for this annotation to be be beside -286 * -287 * @return The name as a string -288 */ -289 String name() default ""; -290 -291 /** The color for the tag for the boolean -292 * -293 * @return The color -294 */ -295 Color color() default Color.NO_COLOR; -296 } -297} +078 @Retention(RetentionPolicy.RUNTIME) +079 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +080 @interface Boolean { +081 /** Store index for this annotation (position in telemetry) +082 * +083 * @return The index +084 */ +085 int index() default -1; +086 +087 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +088 * +089 * @return The priority +090 */ +091 int priority() default -1; +092 +093 /** Store the string when the annotated method returns true +094 * +095 * @return The string +096 */ +097 String trueValue() default "true"; +098 +099 /** Store the string when the annotated method returns false +100 * +101 * @return The string +102 */ +103 String falseValue() default "false"; +104 +105 /** Store the name for this annotation to be be beside +106 * +107 * @return The name as a string +108 */ +109 String name() default ""; +110 +111 } +112} diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Logs.html b/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Logs.html index 7ee63816..921aede7 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Logs.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Logs.html @@ -17,297 +17,112 @@ 004import static java.lang.annotation.ElementType.LOCAL_VARIABLE; 005import static java.lang.annotation.ElementType.METHOD; 006 -007import com.technototes.library.util.Color; -008import java.lang.annotation.Documented; -009import java.lang.annotation.ElementType; -010import java.lang.annotation.Repeatable; -011import java.lang.annotation.Retention; -012import java.lang.annotation.RetentionPolicy; -013import java.lang.annotation.Target; -014 -015/** The root annotation for annotation logging, also doubles as a basic string log -016 * @author Alex Stedman -017 */ -018@Documented -019@Repeatable(Log.Logs.class) -020@Retention(RetentionPolicy.RUNTIME) -021@Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -022public @interface Log { -023 /** Store index for this annotation (position in telemetry) -024 * -025 * @return The index -026 */ -027 int index() default -1; -028 -029 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -030 * -031 * @return The priority -032 */ -033 int priority() default -1; -034 -035 /** Store the name for this annotation to be be beside -036 * -037 * @return The name as a string -038 */ -039 String name() default ""; -040 -041 /** The format for the logged String -042 * -043 * @return The format -044 */ -045 String format() default "%s"; -046 -047 /** The color for the entry -048 * -049 * @return The color -050 */ -051 Color entryColor() default Color.NO_COLOR; +007import java.lang.annotation.Documented; +008import java.lang.annotation.ElementType; +009import java.lang.annotation.Repeatable; +010import java.lang.annotation.Retention; +011import java.lang.annotation.RetentionPolicy; +012import java.lang.annotation.Target; +013 +014/** The root annotation for annotation logging, also doubles as a basic string log +015 * @author Alex Stedman +016 */ +017@Documented +018@Repeatable(Log.Logs.class) +019@Retention(RetentionPolicy.RUNTIME) +020@Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +021public @interface Log { +022 /** Store index for this annotation (position in telemetry) +023 * +024 * @return The index +025 */ +026 int index() default -1; +027 +028 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +029 * +030 * @return The priority +031 */ +032 int priority() default -1; +033 +034 /** Store the name for this annotation to be be beside +035 * +036 * @return The name as a string +037 */ +038 String name() default ""; +039 +040 /** The format for the logged String +041 * +042 * @return The format +043 */ +044 String format() default "%s"; +045 +046 @Documented +047 @Retention(RetentionPolicy.RUNTIME) +048 @Target({ ElementType.FIELD, ElementType.METHOD }) +049 @interface Logs { +050 Log[] value(); +051 } 052 -053 /** The color for the tag for the entry +053 /** Log a number 054 * -055 * @return The color -056 */ -057 Color color() default Color.NO_COLOR; -058 -059 @Documented -060 @Retention(RetentionPolicy.RUNTIME) -061 @Target({ ElementType.FIELD, ElementType.METHOD }) -062 @interface Logs { -063 Log[] value(); -064 } -065 -066 /** Log a number -067 * -068 */ -069 @Retention(RetentionPolicy.RUNTIME) -070 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -071 @interface Number { -072 /** Store index for this annotation (position in telemetry) -073 * -074 * @return The index -075 */ -076 int index() default -1; +055 */ +056 @Retention(RetentionPolicy.RUNTIME) +057 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +058 @interface Number { +059 /** Store index for this annotation (position in telemetry) +060 * +061 * @return The index +062 */ +063 int index() default -1; +064 +065 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +066 * +067 * @return The priority +068 */ +069 int priority() default -1; +070 +071 /** Store the name for this annotation to be be beside +072 * +073 * @return The name as a string +074 */ +075 String name() default ""; +076 } 077 -078 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -079 * -080 * @return The priority -081 */ -082 int priority() default -1; -083 -084 /** Store the name for this annotation to be be beside -085 * -086 * @return The name as a string -087 */ -088 String name() default ""; -089 -090 /** The color for the tag for the number -091 * -092 * @return The color -093 */ -094 Color color() default Color.NO_COLOR; -095 -096 /** The color for the number -097 * -098 * @return The color -099 */ -100 Color numberColor() default Color.NO_COLOR; -101 } -102 -103 /** Log a number, but store it as a number bar -104 * -105 */ -106 @Retention(RetentionPolicy.RUNTIME) -107 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -108 @interface NumberBar { -109 /** Store index for this annotation (position in telemetry) -110 * -111 * @return The index -112 */ -113 int index() default -1; -114 -115 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -116 * -117 * @return The priority -118 */ -119 int priority() default -1; -120 -121 /** Store the min for the number bar to scale to -122 * -123 * @return The min -124 */ -125 double min() default -1; -126 -127 /** Store the max for the number bar to scale to -128 * -129 * @return The max -130 */ -131 double max() default 1; -132 -133 /** Store the scale for the number bar to scale to -134 * -135 * @return The scale -136 */ -137 double scale() default 0.1; -138 -139 /** Store the name for this annotation to be be beside -140 * -141 * @return The name as a string -142 */ -143 String name() default ""; -144 -145 /** The color for the tag for the bar -146 * -147 * @return The color -148 */ -149 Color color() default Color.NO_COLOR; -150 -151 /** The color for the filled in bar color -152 * -153 * @return The color -154 */ -155 Color completeBarColor() default Color.NO_COLOR; -156 -157 /** The color for the not filled in bar color -158 * -159 * @return The color -160 */ -161 Color incompleteBarColor() default Color.NO_COLOR; -162 -163 /** The color for the bar outlines -164 * -165 * @return The color -166 */ -167 Color outline() default Color.NO_COLOR; -168 } -169 -170 @Retention(RetentionPolicy.RUNTIME) -171 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -172 @interface NumberSlider { -173 /** Store index for this annotation (position in telemetry) -174 * -175 * @return The index -176 */ -177 int index() default -1; -178 -179 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -180 * -181 * @return The priority -182 */ -183 int priority() default -1; -184 -185 /** Store the min for the number bar to scale to -186 * -187 * @return The min -188 */ -189 double min() default -1; -190 -191 /** Store the max for the number bar to scale to -192 * -193 * @return The max -194 */ -195 double max() default 1; -196 -197 /** Store the scale for the number bar to scale to -198 * -199 * @return The scale -200 */ -201 double scale() default 0.1; -202 -203 /** Store the name for this annotation to be be beside -204 * -205 * @return The name as a string -206 */ -207 String name() default ""; -208 -209 /** The color for the tag for the slider -210 * -211 * @return The color -212 */ -213 Color color() default Color.NO_COLOR; -214 -215 /** The color for the slider background -216 * -217 * @return The color -218 */ -219 Color sliderBackground() default Color.NO_COLOR; -220 -221 /** The color for the slider outline -222 * -223 * @return The color -224 */ -225 Color outline() default Color.NO_COLOR; -226 -227 /** The color for the slider slide -228 * -229 * @return The color -230 */ -231 Color slider() default Color.NO_COLOR; -232 } -233 -234 @Retention(RetentionPolicy.RUNTIME) -235 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -236 @interface Boolean { -237 /** Store index for this annotation (position in telemetry) -238 * -239 * @return The index -240 */ -241 int index() default -1; -242 -243 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -244 * -245 * @return The priority -246 */ -247 int priority() default -1; -248 -249 /** Store the string when the annotated method returns true -250 * -251 * @return The string -252 */ -253 String trueValue() default "true"; -254 -255 /** The format for when the boolean returns true -256 * -257 * @return The String format -258 */ -259 String trueFormat() default "%s"; -260 -261 /** The color for the true String -262 * -263 * @return The color -264 */ -265 Color trueColor() default Color.NO_COLOR; -266 -267 /** Store the string when the annotated method returns false -268 * -269 * @return The string -270 */ -271 String falseValue() default "false"; -272 -273 /** The format for when the boolean returns false -274 * -275 * @return The String format -276 */ -277 String falseFormat() default "%s"; -278 -279 /** The color for the false String -280 * -281 * @return The color -282 */ -283 Color falseColor() default Color.NO_COLOR; -284 -285 /** Store the name for this annotation to be be beside -286 * -287 * @return The name as a string -288 */ -289 String name() default ""; -290 -291 /** The color for the tag for the boolean -292 * -293 * @return The color -294 */ -295 Color color() default Color.NO_COLOR; -296 } -297} +078 @Retention(RetentionPolicy.RUNTIME) +079 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +080 @interface Boolean { +081 /** Store index for this annotation (position in telemetry) +082 * +083 * @return The index +084 */ +085 int index() default -1; +086 +087 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +088 * +089 * @return The priority +090 */ +091 int priority() default -1; +092 +093 /** Store the string when the annotated method returns true +094 * +095 * @return The string +096 */ +097 String trueValue() default "true"; +098 +099 /** Store the string when the annotated method returns false +100 * +101 * @return The string +102 */ +103 String falseValue() default "false"; +104 +105 /** Store the name for this annotation to be be beside +106 * +107 * @return The name as a string +108 */ +109 String name() default ""; +110 +111 } +112} diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Number.html b/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Number.html index 57a33226..f1ebb311 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Number.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/Log.Number.html @@ -17,297 +17,112 @@ 004import static java.lang.annotation.ElementType.LOCAL_VARIABLE; 005import static java.lang.annotation.ElementType.METHOD; 006 -007import com.technototes.library.util.Color; -008import java.lang.annotation.Documented; -009import java.lang.annotation.ElementType; -010import java.lang.annotation.Repeatable; -011import java.lang.annotation.Retention; -012import java.lang.annotation.RetentionPolicy; -013import java.lang.annotation.Target; -014 -015/** The root annotation for annotation logging, also doubles as a basic string log -016 * @author Alex Stedman -017 */ -018@Documented -019@Repeatable(Log.Logs.class) -020@Retention(RetentionPolicy.RUNTIME) -021@Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -022public @interface Log { -023 /** Store index for this annotation (position in telemetry) -024 * -025 * @return The index -026 */ -027 int index() default -1; -028 -029 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -030 * -031 * @return The priority -032 */ -033 int priority() default -1; -034 -035 /** Store the name for this annotation to be be beside -036 * -037 * @return The name as a string -038 */ -039 String name() default ""; -040 -041 /** The format for the logged String -042 * -043 * @return The format -044 */ -045 String format() default "%s"; -046 -047 /** The color for the entry -048 * -049 * @return The color -050 */ -051 Color entryColor() default Color.NO_COLOR; +007import java.lang.annotation.Documented; +008import java.lang.annotation.ElementType; +009import java.lang.annotation.Repeatable; +010import java.lang.annotation.Retention; +011import java.lang.annotation.RetentionPolicy; +012import java.lang.annotation.Target; +013 +014/** The root annotation for annotation logging, also doubles as a basic string log +015 * @author Alex Stedman +016 */ +017@Documented +018@Repeatable(Log.Logs.class) +019@Retention(RetentionPolicy.RUNTIME) +020@Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +021public @interface Log { +022 /** Store index for this annotation (position in telemetry) +023 * +024 * @return The index +025 */ +026 int index() default -1; +027 +028 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +029 * +030 * @return The priority +031 */ +032 int priority() default -1; +033 +034 /** Store the name for this annotation to be be beside +035 * +036 * @return The name as a string +037 */ +038 String name() default ""; +039 +040 /** The format for the logged String +041 * +042 * @return The format +043 */ +044 String format() default "%s"; +045 +046 @Documented +047 @Retention(RetentionPolicy.RUNTIME) +048 @Target({ ElementType.FIELD, ElementType.METHOD }) +049 @interface Logs { +050 Log[] value(); +051 } 052 -053 /** The color for the tag for the entry +053 /** Log a number 054 * -055 * @return The color -056 */ -057 Color color() default Color.NO_COLOR; -058 -059 @Documented -060 @Retention(RetentionPolicy.RUNTIME) -061 @Target({ ElementType.FIELD, ElementType.METHOD }) -062 @interface Logs { -063 Log[] value(); -064 } -065 -066 /** Log a number -067 * -068 */ -069 @Retention(RetentionPolicy.RUNTIME) -070 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -071 @interface Number { -072 /** Store index for this annotation (position in telemetry) -073 * -074 * @return The index -075 */ -076 int index() default -1; +055 */ +056 @Retention(RetentionPolicy.RUNTIME) +057 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +058 @interface Number { +059 /** Store index for this annotation (position in telemetry) +060 * +061 * @return The index +062 */ +063 int index() default -1; +064 +065 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +066 * +067 * @return The priority +068 */ +069 int priority() default -1; +070 +071 /** Store the name for this annotation to be be beside +072 * +073 * @return The name as a string +074 */ +075 String name() default ""; +076 } 077 -078 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -079 * -080 * @return The priority -081 */ -082 int priority() default -1; -083 -084 /** Store the name for this annotation to be be beside -085 * -086 * @return The name as a string -087 */ -088 String name() default ""; -089 -090 /** The color for the tag for the number -091 * -092 * @return The color -093 */ -094 Color color() default Color.NO_COLOR; -095 -096 /** The color for the number -097 * -098 * @return The color -099 */ -100 Color numberColor() default Color.NO_COLOR; -101 } -102 -103 /** Log a number, but store it as a number bar -104 * -105 */ -106 @Retention(RetentionPolicy.RUNTIME) -107 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -108 @interface NumberBar { -109 /** Store index for this annotation (position in telemetry) -110 * -111 * @return The index -112 */ -113 int index() default -1; -114 -115 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -116 * -117 * @return The priority -118 */ -119 int priority() default -1; -120 -121 /** Store the min for the number bar to scale to -122 * -123 * @return The min -124 */ -125 double min() default -1; -126 -127 /** Store the max for the number bar to scale to -128 * -129 * @return The max -130 */ -131 double max() default 1; -132 -133 /** Store the scale for the number bar to scale to -134 * -135 * @return The scale -136 */ -137 double scale() default 0.1; -138 -139 /** Store the name for this annotation to be be beside -140 * -141 * @return The name as a string -142 */ -143 String name() default ""; -144 -145 /** The color for the tag for the bar -146 * -147 * @return The color -148 */ -149 Color color() default Color.NO_COLOR; -150 -151 /** The color for the filled in bar color -152 * -153 * @return The color -154 */ -155 Color completeBarColor() default Color.NO_COLOR; -156 -157 /** The color for the not filled in bar color -158 * -159 * @return The color -160 */ -161 Color incompleteBarColor() default Color.NO_COLOR; -162 -163 /** The color for the bar outlines -164 * -165 * @return The color -166 */ -167 Color outline() default Color.NO_COLOR; -168 } -169 -170 @Retention(RetentionPolicy.RUNTIME) -171 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -172 @interface NumberSlider { -173 /** Store index for this annotation (position in telemetry) -174 * -175 * @return The index -176 */ -177 int index() default -1; -178 -179 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -180 * -181 * @return The priority -182 */ -183 int priority() default -1; -184 -185 /** Store the min for the number bar to scale to -186 * -187 * @return The min -188 */ -189 double min() default -1; -190 -191 /** Store the max for the number bar to scale to -192 * -193 * @return The max -194 */ -195 double max() default 1; -196 -197 /** Store the scale for the number bar to scale to -198 * -199 * @return The scale -200 */ -201 double scale() default 0.1; -202 -203 /** Store the name for this annotation to be be beside -204 * -205 * @return The name as a string -206 */ -207 String name() default ""; -208 -209 /** The color for the tag for the slider -210 * -211 * @return The color -212 */ -213 Color color() default Color.NO_COLOR; -214 -215 /** The color for the slider background -216 * -217 * @return The color -218 */ -219 Color sliderBackground() default Color.NO_COLOR; -220 -221 /** The color for the slider outline -222 * -223 * @return The color -224 */ -225 Color outline() default Color.NO_COLOR; -226 -227 /** The color for the slider slide -228 * -229 * @return The color -230 */ -231 Color slider() default Color.NO_COLOR; -232 } -233 -234 @Retention(RetentionPolicy.RUNTIME) -235 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -236 @interface Boolean { -237 /** Store index for this annotation (position in telemetry) -238 * -239 * @return The index -240 */ -241 int index() default -1; -242 -243 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -244 * -245 * @return The priority -246 */ -247 int priority() default -1; -248 -249 /** Store the string when the annotated method returns true -250 * -251 * @return The string -252 */ -253 String trueValue() default "true"; -254 -255 /** The format for when the boolean returns true -256 * -257 * @return The String format -258 */ -259 String trueFormat() default "%s"; -260 -261 /** The color for the true String -262 * -263 * @return The color -264 */ -265 Color trueColor() default Color.NO_COLOR; -266 -267 /** Store the string when the annotated method returns false -268 * -269 * @return The string -270 */ -271 String falseValue() default "false"; -272 -273 /** The format for when the boolean returns false -274 * -275 * @return The String format -276 */ -277 String falseFormat() default "%s"; -278 -279 /** The color for the false String -280 * -281 * @return The color -282 */ -283 Color falseColor() default Color.NO_COLOR; -284 -285 /** Store the name for this annotation to be be beside -286 * -287 * @return The name as a string -288 */ -289 String name() default ""; -290 -291 /** The color for the tag for the boolean -292 * -293 * @return The color -294 */ -295 Color color() default Color.NO_COLOR; -296 } -297} +078 @Retention(RetentionPolicy.RUNTIME) +079 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +080 @interface Boolean { +081 /** Store index for this annotation (position in telemetry) +082 * +083 * @return The index +084 */ +085 int index() default -1; +086 +087 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +088 * +089 * @return The priority +090 */ +091 int priority() default -1; +092 +093 /** Store the string when the annotated method returns true +094 * +095 * @return The string +096 */ +097 String trueValue() default "true"; +098 +099 /** Store the string when the annotated method returns false +100 * +101 * @return The string +102 */ +103 String falseValue() default "false"; +104 +105 /** Store the name for this annotation to be be beside +106 * +107 * @return The name as a string +108 */ +109 String name() default ""; +110 +111 } +112} diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.NumberBar.html b/docs/TechnoLib/src-html/com/technototes/library/logger/Log.NumberBar.html deleted file mode 100644 index 15ec4e59..00000000 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.NumberBar.html +++ /dev/null @@ -1,375 +0,0 @@ - - - - -Source code - - - - - - -
    -
    -
    001package com.technototes.library.logger;
    -002
    -003import static java.lang.annotation.ElementType.FIELD;
    -004import static java.lang.annotation.ElementType.LOCAL_VARIABLE;
    -005import static java.lang.annotation.ElementType.METHOD;
    -006
    -007import com.technototes.library.util.Color;
    -008import java.lang.annotation.Documented;
    -009import java.lang.annotation.ElementType;
    -010import java.lang.annotation.Repeatable;
    -011import java.lang.annotation.Retention;
    -012import java.lang.annotation.RetentionPolicy;
    -013import java.lang.annotation.Target;
    -014
    -015/** The root annotation for annotation logging, also doubles as a basic string log
    -016 * @author Alex Stedman
    -017 */
    -018@Documented
    -019@Repeatable(Log.Logs.class)
    -020@Retention(RetentionPolicy.RUNTIME)
    -021@Target(value = { FIELD, LOCAL_VARIABLE, METHOD })
    -022public @interface Log {
    -023    /** Store index for this annotation (position in telemetry)
    -024     *
    -025     * @return The index
    -026     */
    -027    int index() default -1;
    -028
    -029    /** Store priority for this log entry (to pick the most wanted entry over others with same index)
    -030     *
    -031     * @return The priority
    -032     */
    -033    int priority() default -1;
    -034
    -035    /** Store the name for this annotation to be be beside
    -036     *
    -037     * @return The name as a string
    -038     */
    -039    String name() default "";
    -040
    -041    /** The format for the logged String
    -042     *
    -043     * @return The format
    -044     */
    -045    String format() default "%s";
    -046
    -047    /** The color for the entry
    -048     *
    -049     * @return The color
    -050     */
    -051    Color entryColor() default Color.NO_COLOR;
    -052
    -053    /** The color for the tag for the entry
    -054     *
    -055     * @return The color
    -056     */
    -057    Color color() default Color.NO_COLOR;
    -058
    -059    @Documented
    -060    @Retention(RetentionPolicy.RUNTIME)
    -061    @Target({ ElementType.FIELD, ElementType.METHOD })
    -062    @interface Logs {
    -063        Log[] value();
    -064    }
    -065
    -066    /** Log a number
    -067     *
    -068     */
    -069    @Retention(RetentionPolicy.RUNTIME)
    -070    @Target(value = { FIELD, LOCAL_VARIABLE, METHOD })
    -071    @interface Number {
    -072        /** Store index for this annotation (position in telemetry)
    -073         *
    -074         * @return The index
    -075         */
    -076        int index() default -1;
    -077
    -078        /** Store priority for this log entry (to pick the most wanted entry over others with same index)
    -079         *
    -080         * @return The priority
    -081         */
    -082        int priority() default -1;
    -083
    -084        /** Store the name for this annotation to be be beside
    -085         *
    -086         * @return The name as a string
    -087         */
    -088        String name() default "";
    -089
    -090        /** The color for the tag for the number
    -091         *
    -092         * @return The color
    -093         */
    -094        Color color() default Color.NO_COLOR;
    -095
    -096        /** The color for the number
    -097         *
    -098         * @return The color
    -099         */
    -100        Color numberColor() default Color.NO_COLOR;
    -101    }
    -102
    -103    /** Log a number, but store it as a number bar
    -104     *
    -105     */
    -106    @Retention(RetentionPolicy.RUNTIME)
    -107    @Target(value = { FIELD, LOCAL_VARIABLE, METHOD })
    -108    @interface NumberBar {
    -109        /** Store index for this annotation (position in telemetry)
    -110         *
    -111         * @return The index
    -112         */
    -113        int index() default -1;
    -114
    -115        /** Store priority for this log entry (to pick the most wanted entry over others with same index)
    -116         *
    -117         * @return The priority
    -118         */
    -119        int priority() default -1;
    -120
    -121        /** Store the min for the number bar to scale to
    -122         *
    -123         * @return The min
    -124         */
    -125        double min() default -1;
    -126
    -127        /** Store the max for the number bar to scale to
    -128         *
    -129         * @return The max
    -130         */
    -131        double max() default 1;
    -132
    -133        /** Store the scale for the number bar to scale to
    -134         *
    -135         * @return The scale
    -136         */
    -137        double scale() default 0.1;
    -138
    -139        /** Store the name for this annotation to be be beside
    -140         *
    -141         * @return The name as a string
    -142         */
    -143        String name() default "";
    -144
    -145        /** The color for the tag for the bar
    -146         *
    -147         * @return The color
    -148         */
    -149        Color color() default Color.NO_COLOR;
    -150
    -151        /** The color for the filled in bar color
    -152         *
    -153         * @return The color
    -154         */
    -155        Color completeBarColor() default Color.NO_COLOR;
    -156
    -157        /** The color for the not filled in bar color
    -158         *
    -159         * @return The color
    -160         */
    -161        Color incompleteBarColor() default Color.NO_COLOR;
    -162
    -163        /** The color for the bar outlines
    -164         *
    -165         * @return The color
    -166         */
    -167        Color outline() default Color.NO_COLOR;
    -168    }
    -169
    -170    @Retention(RetentionPolicy.RUNTIME)
    -171    @Target(value = { FIELD, LOCAL_VARIABLE, METHOD })
    -172    @interface NumberSlider {
    -173        /** Store index for this annotation (position in telemetry)
    -174         *
    -175         * @return The index
    -176         */
    -177        int index() default -1;
    -178
    -179        /** Store priority for this log entry (to pick the most wanted entry over others with same index)
    -180         *
    -181         * @return The priority
    -182         */
    -183        int priority() default -1;
    -184
    -185        /** Store the min for the number bar to scale to
    -186         *
    -187         * @return The min
    -188         */
    -189        double min() default -1;
    -190
    -191        /** Store the max for the number bar to scale to
    -192         *
    -193         * @return The max
    -194         */
    -195        double max() default 1;
    -196
    -197        /** Store the scale for the number bar to scale to
    -198         *
    -199         * @return The scale
    -200         */
    -201        double scale() default 0.1;
    -202
    -203        /** Store the name for this annotation to be be beside
    -204         *
    -205         * @return The name as a string
    -206         */
    -207        String name() default "";
    -208
    -209        /** The color for the tag for the slider
    -210         *
    -211         * @return The color
    -212         */
    -213        Color color() default Color.NO_COLOR;
    -214
    -215        /** The color for the slider background
    -216         *
    -217         * @return The color
    -218         */
    -219        Color sliderBackground() default Color.NO_COLOR;
    -220
    -221        /** The color for the slider outline
    -222         *
    -223         * @return The color
    -224         */
    -225        Color outline() default Color.NO_COLOR;
    -226
    -227        /** The color for the slider slide
    -228         *
    -229         * @return The color
    -230         */
    -231        Color slider() default Color.NO_COLOR;
    -232    }
    -233
    -234    @Retention(RetentionPolicy.RUNTIME)
    -235    @Target(value = { FIELD, LOCAL_VARIABLE, METHOD })
    -236    @interface Boolean {
    -237        /** Store index for this annotation (position in telemetry)
    -238         *
    -239         * @return The index
    -240         */
    -241        int index() default -1;
    -242
    -243        /** Store priority for this log entry (to pick the most wanted entry over others with same index)
    -244         *
    -245         * @return The priority
    -246         */
    -247        int priority() default -1;
    -248
    -249        /** Store the string when the annotated method returns true
    -250         *
    -251         * @return The string
    -252         */
    -253        String trueValue() default "true";
    -254
    -255        /** The format for when the boolean returns true
    -256         *
    -257         * @return The String format
    -258         */
    -259        String trueFormat() default "%s";
    -260
    -261        /** The color for the true String
    -262         *
    -263         * @return The color
    -264         */
    -265        Color trueColor() default Color.NO_COLOR;
    -266
    -267        /** Store the string when the annotated method returns false
    -268         *
    -269         * @return The string
    -270         */
    -271        String falseValue() default "false";
    -272
    -273        /** The format for when the boolean returns false
    -274         *
    -275         * @return The String format
    -276         */
    -277        String falseFormat() default "%s";
    -278
    -279        /** The color for the false String
    -280         *
    -281         * @return The color
    -282         */
    -283        Color falseColor() default Color.NO_COLOR;
    -284
    -285        /** Store the name for this annotation to be be beside
    -286         *
    -287         * @return The name as a string
    -288         */
    -289        String name() default "";
    -290
    -291        /** The color for the tag for the boolean
    -292         *
    -293         * @return The color
    -294         */
    -295        Color color() default Color.NO_COLOR;
    -296    }
    -297}
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    - - diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.NumberSlider.html b/docs/TechnoLib/src-html/com/technototes/library/logger/Log.NumberSlider.html deleted file mode 100644 index 9601b5ef..00000000 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.NumberSlider.html +++ /dev/null @@ -1,375 +0,0 @@ - - - - -Source code - - - - - - -
    -
    -
    001package com.technototes.library.logger;
    -002
    -003import static java.lang.annotation.ElementType.FIELD;
    -004import static java.lang.annotation.ElementType.LOCAL_VARIABLE;
    -005import static java.lang.annotation.ElementType.METHOD;
    -006
    -007import com.technototes.library.util.Color;
    -008import java.lang.annotation.Documented;
    -009import java.lang.annotation.ElementType;
    -010import java.lang.annotation.Repeatable;
    -011import java.lang.annotation.Retention;
    -012import java.lang.annotation.RetentionPolicy;
    -013import java.lang.annotation.Target;
    -014
    -015/** The root annotation for annotation logging, also doubles as a basic string log
    -016 * @author Alex Stedman
    -017 */
    -018@Documented
    -019@Repeatable(Log.Logs.class)
    -020@Retention(RetentionPolicy.RUNTIME)
    -021@Target(value = { FIELD, LOCAL_VARIABLE, METHOD })
    -022public @interface Log {
    -023    /** Store index for this annotation (position in telemetry)
    -024     *
    -025     * @return The index
    -026     */
    -027    int index() default -1;
    -028
    -029    /** Store priority for this log entry (to pick the most wanted entry over others with same index)
    -030     *
    -031     * @return The priority
    -032     */
    -033    int priority() default -1;
    -034
    -035    /** Store the name for this annotation to be be beside
    -036     *
    -037     * @return The name as a string
    -038     */
    -039    String name() default "";
    -040
    -041    /** The format for the logged String
    -042     *
    -043     * @return The format
    -044     */
    -045    String format() default "%s";
    -046
    -047    /** The color for the entry
    -048     *
    -049     * @return The color
    -050     */
    -051    Color entryColor() default Color.NO_COLOR;
    -052
    -053    /** The color for the tag for the entry
    -054     *
    -055     * @return The color
    -056     */
    -057    Color color() default Color.NO_COLOR;
    -058
    -059    @Documented
    -060    @Retention(RetentionPolicy.RUNTIME)
    -061    @Target({ ElementType.FIELD, ElementType.METHOD })
    -062    @interface Logs {
    -063        Log[] value();
    -064    }
    -065
    -066    /** Log a number
    -067     *
    -068     */
    -069    @Retention(RetentionPolicy.RUNTIME)
    -070    @Target(value = { FIELD, LOCAL_VARIABLE, METHOD })
    -071    @interface Number {
    -072        /** Store index for this annotation (position in telemetry)
    -073         *
    -074         * @return The index
    -075         */
    -076        int index() default -1;
    -077
    -078        /** Store priority for this log entry (to pick the most wanted entry over others with same index)
    -079         *
    -080         * @return The priority
    -081         */
    -082        int priority() default -1;
    -083
    -084        /** Store the name for this annotation to be be beside
    -085         *
    -086         * @return The name as a string
    -087         */
    -088        String name() default "";
    -089
    -090        /** The color for the tag for the number
    -091         *
    -092         * @return The color
    -093         */
    -094        Color color() default Color.NO_COLOR;
    -095
    -096        /** The color for the number
    -097         *
    -098         * @return The color
    -099         */
    -100        Color numberColor() default Color.NO_COLOR;
    -101    }
    -102
    -103    /** Log a number, but store it as a number bar
    -104     *
    -105     */
    -106    @Retention(RetentionPolicy.RUNTIME)
    -107    @Target(value = { FIELD, LOCAL_VARIABLE, METHOD })
    -108    @interface NumberBar {
    -109        /** Store index for this annotation (position in telemetry)
    -110         *
    -111         * @return The index
    -112         */
    -113        int index() default -1;
    -114
    -115        /** Store priority for this log entry (to pick the most wanted entry over others with same index)
    -116         *
    -117         * @return The priority
    -118         */
    -119        int priority() default -1;
    -120
    -121        /** Store the min for the number bar to scale to
    -122         *
    -123         * @return The min
    -124         */
    -125        double min() default -1;
    -126
    -127        /** Store the max for the number bar to scale to
    -128         *
    -129         * @return The max
    -130         */
    -131        double max() default 1;
    -132
    -133        /** Store the scale for the number bar to scale to
    -134         *
    -135         * @return The scale
    -136         */
    -137        double scale() default 0.1;
    -138
    -139        /** Store the name for this annotation to be be beside
    -140         *
    -141         * @return The name as a string
    -142         */
    -143        String name() default "";
    -144
    -145        /** The color for the tag for the bar
    -146         *
    -147         * @return The color
    -148         */
    -149        Color color() default Color.NO_COLOR;
    -150
    -151        /** The color for the filled in bar color
    -152         *
    -153         * @return The color
    -154         */
    -155        Color completeBarColor() default Color.NO_COLOR;
    -156
    -157        /** The color for the not filled in bar color
    -158         *
    -159         * @return The color
    -160         */
    -161        Color incompleteBarColor() default Color.NO_COLOR;
    -162
    -163        /** The color for the bar outlines
    -164         *
    -165         * @return The color
    -166         */
    -167        Color outline() default Color.NO_COLOR;
    -168    }
    -169
    -170    @Retention(RetentionPolicy.RUNTIME)
    -171    @Target(value = { FIELD, LOCAL_VARIABLE, METHOD })
    -172    @interface NumberSlider {
    -173        /** Store index for this annotation (position in telemetry)
    -174         *
    -175         * @return The index
    -176         */
    -177        int index() default -1;
    -178
    -179        /** Store priority for this log entry (to pick the most wanted entry over others with same index)
    -180         *
    -181         * @return The priority
    -182         */
    -183        int priority() default -1;
    -184
    -185        /** Store the min for the number bar to scale to
    -186         *
    -187         * @return The min
    -188         */
    -189        double min() default -1;
    -190
    -191        /** Store the max for the number bar to scale to
    -192         *
    -193         * @return The max
    -194         */
    -195        double max() default 1;
    -196
    -197        /** Store the scale for the number bar to scale to
    -198         *
    -199         * @return The scale
    -200         */
    -201        double scale() default 0.1;
    -202
    -203        /** Store the name for this annotation to be be beside
    -204         *
    -205         * @return The name as a string
    -206         */
    -207        String name() default "";
    -208
    -209        /** The color for the tag for the slider
    -210         *
    -211         * @return The color
    -212         */
    -213        Color color() default Color.NO_COLOR;
    -214
    -215        /** The color for the slider background
    -216         *
    -217         * @return The color
    -218         */
    -219        Color sliderBackground() default Color.NO_COLOR;
    -220
    -221        /** The color for the slider outline
    -222         *
    -223         * @return The color
    -224         */
    -225        Color outline() default Color.NO_COLOR;
    -226
    -227        /** The color for the slider slide
    -228         *
    -229         * @return The color
    -230         */
    -231        Color slider() default Color.NO_COLOR;
    -232    }
    -233
    -234    @Retention(RetentionPolicy.RUNTIME)
    -235    @Target(value = { FIELD, LOCAL_VARIABLE, METHOD })
    -236    @interface Boolean {
    -237        /** Store index for this annotation (position in telemetry)
    -238         *
    -239         * @return The index
    -240         */
    -241        int index() default -1;
    -242
    -243        /** Store priority for this log entry (to pick the most wanted entry over others with same index)
    -244         *
    -245         * @return The priority
    -246         */
    -247        int priority() default -1;
    -248
    -249        /** Store the string when the annotated method returns true
    -250         *
    -251         * @return The string
    -252         */
    -253        String trueValue() default "true";
    -254
    -255        /** The format for when the boolean returns true
    -256         *
    -257         * @return The String format
    -258         */
    -259        String trueFormat() default "%s";
    -260
    -261        /** The color for the true String
    -262         *
    -263         * @return The color
    -264         */
    -265        Color trueColor() default Color.NO_COLOR;
    -266
    -267        /** Store the string when the annotated method returns false
    -268         *
    -269         * @return The string
    -270         */
    -271        String falseValue() default "false";
    -272
    -273        /** The format for when the boolean returns false
    -274         *
    -275         * @return The String format
    -276         */
    -277        String falseFormat() default "%s";
    -278
    -279        /** The color for the false String
    -280         *
    -281         * @return The color
    -282         */
    -283        Color falseColor() default Color.NO_COLOR;
    -284
    -285        /** Store the name for this annotation to be be beside
    -286         *
    -287         * @return The name as a string
    -288         */
    -289        String name() default "";
    -290
    -291        /** The color for the tag for the boolean
    -292         *
    -293         * @return The color
    -294         */
    -295        Color color() default Color.NO_COLOR;
    -296    }
    -297}
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    - - diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.html b/docs/TechnoLib/src-html/com/technototes/library/logger/Log.html index b7356acb..d90faa60 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/Log.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/Log.html @@ -17,297 +17,112 @@ 004import static java.lang.annotation.ElementType.LOCAL_VARIABLE; 005import static java.lang.annotation.ElementType.METHOD; 006 -007import com.technototes.library.util.Color; -008import java.lang.annotation.Documented; -009import java.lang.annotation.ElementType; -010import java.lang.annotation.Repeatable; -011import java.lang.annotation.Retention; -012import java.lang.annotation.RetentionPolicy; -013import java.lang.annotation.Target; -014 -015/** The root annotation for annotation logging, also doubles as a basic string log -016 * @author Alex Stedman -017 */ -018@Documented -019@Repeatable(Log.Logs.class) -020@Retention(RetentionPolicy.RUNTIME) -021@Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -022public @interface Log { -023 /** Store index for this annotation (position in telemetry) -024 * -025 * @return The index -026 */ -027 int index() default -1; -028 -029 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -030 * -031 * @return The priority -032 */ -033 int priority() default -1; -034 -035 /** Store the name for this annotation to be be beside -036 * -037 * @return The name as a string -038 */ -039 String name() default ""; -040 -041 /** The format for the logged String -042 * -043 * @return The format -044 */ -045 String format() default "%s"; -046 -047 /** The color for the entry -048 * -049 * @return The color -050 */ -051 Color entryColor() default Color.NO_COLOR; +007import java.lang.annotation.Documented; +008import java.lang.annotation.ElementType; +009import java.lang.annotation.Repeatable; +010import java.lang.annotation.Retention; +011import java.lang.annotation.RetentionPolicy; +012import java.lang.annotation.Target; +013 +014/** The root annotation for annotation logging, also doubles as a basic string log +015 * @author Alex Stedman +016 */ +017@Documented +018@Repeatable(Log.Logs.class) +019@Retention(RetentionPolicy.RUNTIME) +020@Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +021public @interface Log { +022 /** Store index for this annotation (position in telemetry) +023 * +024 * @return The index +025 */ +026 int index() default -1; +027 +028 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +029 * +030 * @return The priority +031 */ +032 int priority() default -1; +033 +034 /** Store the name for this annotation to be be beside +035 * +036 * @return The name as a string +037 */ +038 String name() default ""; +039 +040 /** The format for the logged String +041 * +042 * @return The format +043 */ +044 String format() default "%s"; +045 +046 @Documented +047 @Retention(RetentionPolicy.RUNTIME) +048 @Target({ ElementType.FIELD, ElementType.METHOD }) +049 @interface Logs { +050 Log[] value(); +051 } 052 -053 /** The color for the tag for the entry +053 /** Log a number 054 * -055 * @return The color -056 */ -057 Color color() default Color.NO_COLOR; -058 -059 @Documented -060 @Retention(RetentionPolicy.RUNTIME) -061 @Target({ ElementType.FIELD, ElementType.METHOD }) -062 @interface Logs { -063 Log[] value(); -064 } -065 -066 /** Log a number -067 * -068 */ -069 @Retention(RetentionPolicy.RUNTIME) -070 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -071 @interface Number { -072 /** Store index for this annotation (position in telemetry) -073 * -074 * @return The index -075 */ -076 int index() default -1; +055 */ +056 @Retention(RetentionPolicy.RUNTIME) +057 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +058 @interface Number { +059 /** Store index for this annotation (position in telemetry) +060 * +061 * @return The index +062 */ +063 int index() default -1; +064 +065 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +066 * +067 * @return The priority +068 */ +069 int priority() default -1; +070 +071 /** Store the name for this annotation to be be beside +072 * +073 * @return The name as a string +074 */ +075 String name() default ""; +076 } 077 -078 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -079 * -080 * @return The priority -081 */ -082 int priority() default -1; -083 -084 /** Store the name for this annotation to be be beside -085 * -086 * @return The name as a string -087 */ -088 String name() default ""; -089 -090 /** The color for the tag for the number -091 * -092 * @return The color -093 */ -094 Color color() default Color.NO_COLOR; -095 -096 /** The color for the number -097 * -098 * @return The color -099 */ -100 Color numberColor() default Color.NO_COLOR; -101 } -102 -103 /** Log a number, but store it as a number bar -104 * -105 */ -106 @Retention(RetentionPolicy.RUNTIME) -107 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -108 @interface NumberBar { -109 /** Store index for this annotation (position in telemetry) -110 * -111 * @return The index -112 */ -113 int index() default -1; -114 -115 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -116 * -117 * @return The priority -118 */ -119 int priority() default -1; -120 -121 /** Store the min for the number bar to scale to -122 * -123 * @return The min -124 */ -125 double min() default -1; -126 -127 /** Store the max for the number bar to scale to -128 * -129 * @return The max -130 */ -131 double max() default 1; -132 -133 /** Store the scale for the number bar to scale to -134 * -135 * @return The scale -136 */ -137 double scale() default 0.1; -138 -139 /** Store the name for this annotation to be be beside -140 * -141 * @return The name as a string -142 */ -143 String name() default ""; -144 -145 /** The color for the tag for the bar -146 * -147 * @return The color -148 */ -149 Color color() default Color.NO_COLOR; -150 -151 /** The color for the filled in bar color -152 * -153 * @return The color -154 */ -155 Color completeBarColor() default Color.NO_COLOR; -156 -157 /** The color for the not filled in bar color -158 * -159 * @return The color -160 */ -161 Color incompleteBarColor() default Color.NO_COLOR; -162 -163 /** The color for the bar outlines -164 * -165 * @return The color -166 */ -167 Color outline() default Color.NO_COLOR; -168 } -169 -170 @Retention(RetentionPolicy.RUNTIME) -171 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -172 @interface NumberSlider { -173 /** Store index for this annotation (position in telemetry) -174 * -175 * @return The index -176 */ -177 int index() default -1; -178 -179 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -180 * -181 * @return The priority -182 */ -183 int priority() default -1; -184 -185 /** Store the min for the number bar to scale to -186 * -187 * @return The min -188 */ -189 double min() default -1; -190 -191 /** Store the max for the number bar to scale to -192 * -193 * @return The max -194 */ -195 double max() default 1; -196 -197 /** Store the scale for the number bar to scale to -198 * -199 * @return The scale -200 */ -201 double scale() default 0.1; -202 -203 /** Store the name for this annotation to be be beside -204 * -205 * @return The name as a string -206 */ -207 String name() default ""; -208 -209 /** The color for the tag for the slider -210 * -211 * @return The color -212 */ -213 Color color() default Color.NO_COLOR; -214 -215 /** The color for the slider background -216 * -217 * @return The color -218 */ -219 Color sliderBackground() default Color.NO_COLOR; -220 -221 /** The color for the slider outline -222 * -223 * @return The color -224 */ -225 Color outline() default Color.NO_COLOR; -226 -227 /** The color for the slider slide -228 * -229 * @return The color -230 */ -231 Color slider() default Color.NO_COLOR; -232 } -233 -234 @Retention(RetentionPolicy.RUNTIME) -235 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -236 @interface Boolean { -237 /** Store index for this annotation (position in telemetry) -238 * -239 * @return The index -240 */ -241 int index() default -1; -242 -243 /** Store priority for this log entry (to pick the most wanted entry over others with same index) -244 * -245 * @return The priority -246 */ -247 int priority() default -1; -248 -249 /** Store the string when the annotated method returns true -250 * -251 * @return The string -252 */ -253 String trueValue() default "true"; -254 -255 /** The format for when the boolean returns true -256 * -257 * @return The String format -258 */ -259 String trueFormat() default "%s"; -260 -261 /** The color for the true String -262 * -263 * @return The color -264 */ -265 Color trueColor() default Color.NO_COLOR; -266 -267 /** Store the string when the annotated method returns false -268 * -269 * @return The string -270 */ -271 String falseValue() default "false"; -272 -273 /** The format for when the boolean returns false -274 * -275 * @return The String format -276 */ -277 String falseFormat() default "%s"; -278 -279 /** The color for the false String -280 * -281 * @return The color -282 */ -283 Color falseColor() default Color.NO_COLOR; -284 -285 /** Store the name for this annotation to be be beside -286 * -287 * @return The name as a string -288 */ -289 String name() default ""; -290 -291 /** The color for the tag for the boolean -292 * -293 * @return The color -294 */ -295 Color color() default Color.NO_COLOR; -296 } -297} +078 @Retention(RetentionPolicy.RUNTIME) +079 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) +080 @interface Boolean { +081 /** Store index for this annotation (position in telemetry) +082 * +083 * @return The index +084 */ +085 int index() default -1; +086 +087 /** Store priority for this log entry (to pick the most wanted entry over others with same index) +088 * +089 * @return The priority +090 */ +091 int priority() default -1; +092 +093 /** Store the string when the annotated method returns true +094 * +095 * @return The string +096 */ +097 String trueValue() default "true"; +098 +099 /** Store the string when the annotated method returns false +100 * +101 * @return The string +102 */ +103 String falseValue() default "false"; +104 +105 /** Store the name for this annotation to be be beside +106 * +107 * @return The name as a string +108 */ +109 String name() default ""; +110 +111 } +112} diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Blacklist.html b/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.AllowList.html similarity index 96% rename from docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Blacklist.html rename to docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.AllowList.html index 6441f4be..190a68b5 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Blacklist.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.AllowList.html @@ -4,7 +4,7 @@ Source code - + @@ -45,26 +45,26 @@ 032 boolean duringInit() default false; 033 } 034 -035 /** Annotation for Whitelisting Opmodes to log this item +035 /** Annotation for allowing Opmodes to log this item 036 * 037 */ 038 @Retention(RetentionPolicy.RUNTIME) 039 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -040 @interface Whitelist { -041 /** The whitelisted opmodes +040 @interface AllowList { +041 /** The allowed opmodes 042 * 043 * @return Opmode Classes 044 */ 045 Class<?>[] value(); 046 } 047 -048 /** Annotation for Blacklisting Opmodes to log this item +048 /** Annotation for denying Opmodes to log this item 049 * 050 */ 051 @Retention(RetentionPolicy.RUNTIME) 052 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -053 @interface Blacklist { -054 /** The blacklisted opmodes +053 @interface DenyList { +054 /** The denied opmodes 055 * 056 * @return Opmode Classes 057 */ diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Whitelist.html b/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.DenyList.html similarity index 96% rename from docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Whitelist.html rename to docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.DenyList.html index 0abba31c..ad893587 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Whitelist.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.DenyList.html @@ -4,7 +4,7 @@ Source code - + @@ -45,26 +45,26 @@ 032 boolean duringInit() default false; 033 } 034 -035 /** Annotation for Whitelisting Opmodes to log this item +035 /** Annotation for allowing Opmodes to log this item 036 * 037 */ 038 @Retention(RetentionPolicy.RUNTIME) 039 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -040 @interface Whitelist { -041 /** The whitelisted opmodes +040 @interface AllowList { +041 /** The allowed opmodes 042 * 043 * @return Opmode Classes 044 */ 045 Class<?>[] value(); 046 } 047 -048 /** Annotation for Blacklisting Opmodes to log this item +048 /** Annotation for denying Opmodes to log this item 049 * 050 */ 051 @Retention(RetentionPolicy.RUNTIME) 052 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -053 @interface Blacklist { -054 /** The blacklisted opmodes +053 @interface DenyList { +054 /** The denied opmodes 055 * 056 * @return Opmode Classes 057 */ diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Disabled.html b/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Disabled.html index 83a4001a..9280604e 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Disabled.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Disabled.html @@ -45,26 +45,26 @@ 032 boolean duringInit() default false; 033 } 034 -035 /** Annotation for Whitelisting Opmodes to log this item +035 /** Annotation for allowing Opmodes to log this item 036 * 037 */ 038 @Retention(RetentionPolicy.RUNTIME) 039 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -040 @interface Whitelist { -041 /** The whitelisted opmodes +040 @interface AllowList { +041 /** The allowed opmodes 042 * 043 * @return Opmode Classes 044 */ 045 Class<?>[] value(); 046 } 047 -048 /** Annotation for Blacklisting Opmodes to log this item +048 /** Annotation for denying Opmodes to log this item 049 * 050 */ 051 @Retention(RetentionPolicy.RUNTIME) 052 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -053 @interface Blacklist { -054 /** The blacklisted opmodes +053 @interface DenyList { +054 /** The denied opmodes 055 * 056 * @return Opmode Classes 057 */ diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Run.html b/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Run.html index 206f810c..b40f8d2d 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Run.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.Run.html @@ -45,26 +45,26 @@ 032 boolean duringInit() default false; 033 } 034 -035 /** Annotation for Whitelisting Opmodes to log this item +035 /** Annotation for allowing Opmodes to log this item 036 * 037 */ 038 @Retention(RetentionPolicy.RUNTIME) 039 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -040 @interface Whitelist { -041 /** The whitelisted opmodes +040 @interface AllowList { +041 /** The allowed opmodes 042 * 043 * @return Opmode Classes 044 */ 045 Class<?>[] value(); 046 } 047 -048 /** Annotation for Blacklisting Opmodes to log this item +048 /** Annotation for denying Opmodes to log this item 049 * 050 */ 051 @Retention(RetentionPolicy.RUNTIME) 052 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -053 @interface Blacklist { -054 /** The blacklisted opmodes +053 @interface DenyList { +054 /** The denied opmodes 055 * 056 * @return Opmode Classes 057 */ diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.html b/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.html index 38073f2d..18385b64 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/LogConfig.html @@ -45,26 +45,26 @@ 032 boolean duringInit() default false; 033 } 034 -035 /** Annotation for Whitelisting Opmodes to log this item +035 /** Annotation for allowing Opmodes to log this item 036 * 037 */ 038 @Retention(RetentionPolicy.RUNTIME) 039 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -040 @interface Whitelist { -041 /** The whitelisted opmodes +040 @interface AllowList { +041 /** The allowed opmodes 042 * 043 * @return Opmode Classes 044 */ 045 Class<?>[] value(); 046 } 047 -048 /** Annotation for Blacklisting Opmodes to log this item +048 /** Annotation for denying Opmodes to log this item 049 * 050 */ 051 @Retention(RetentionPolicy.RUNTIME) 052 @Target(value = { FIELD, LOCAL_VARIABLE, METHOD }) -053 @interface Blacklist { -054 /** The blacklisted opmodes +053 @interface DenyList { +054 /** The denied opmodes 055 * 056 * @return Opmode Classes 057 */ diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/Logger.html b/docs/TechnoLib/src-html/com/technototes/library/logger/Logger.html index 8559cd8d..8b511079 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/Logger.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/Logger.html @@ -16,316 +16,274 @@ 003import com.qualcomm.robotcore.eventloop.opmode.OpMode; 004import com.technototes.library.logger.entry.BooleanEntry; 005import com.technototes.library.logger.entry.Entry; -006import com.technototes.library.logger.entry.NumberBarEntry; -007import com.technototes.library.logger.entry.NumberEntry; -008import com.technototes.library.logger.entry.NumberSliderEntry; -009import com.technototes.library.logger.entry.StringEntry; -010import java.lang.annotation.Annotation; -011import java.lang.reflect.Field; -012import java.lang.reflect.InvocationTargetException; -013import java.lang.reflect.Method; -014import java.sql.Array; -015import java.util.ArrayList; -016import java.util.Arrays; -017import java.util.LinkedHashSet; -018import java.util.List; -019import java.util.Set; -020import java.util.function.BooleanSupplier; -021import java.util.function.DoubleSupplier; -022import java.util.function.IntSupplier; -023import java.util.function.Supplier; -024import org.firstinspires.ftc.robotcore.external.Telemetry; -025 -026/** -027 * The class to manage logging -028 * -029 * @author Alex Stedman -030 */ -031public class Logger { -032 -033 public Entry<?>[] runEntries; -034 public Entry<?>[] initEntries; -035 private final Set<Entry<?>> unindexedRunEntries; -036 private final Set<Entry<?>> unindexedInitEntries; -037 private final Telemetry telemetry; -038 private final OpMode opMode; -039 /** -040 * The divider between the tag and the entry for telemetry (default ':') -041 */ -042 public char captionDivider = ':'; -043 -044 /** -045 * Instantiate the logger -046 * -047 * @param op The OpMode class -048 */ -049 public Logger(OpMode op) { -050 opMode = op; -051 telemetry = op.telemetry; -052 telemetry.setDisplayFormat(Telemetry.DisplayFormat.HTML); -053 unindexedRunEntries = new LinkedHashSet<>(); -054 unindexedInitEntries = new LinkedHashSet<>(); -055 configure(op); -056 runEntries = generate(unindexedRunEntries); -057 initEntries = generate(unindexedInitEntries); -058 } -059 -060 private void configure(Object root) { -061 for (Field field : root.getClass().getFields()) { -062 try { -063 Object o = field.get(root); -064 if (isFieldAllowed(field)) { -065 if (o instanceof Loggable) { -066 configure(o); -067 } else if ( -068 field.isAnnotationPresent(Log.class) || -069 field.isAnnotationPresent(Log.Number.class) || -070 field.isAnnotationPresent(Log.NumberSlider.class) || -071 field.isAnnotationPresent(Log.NumberBar.class) || -072 field.isAnnotationPresent(Log.Boolean.class) -073 ) { -074 if (field.getType().isPrimitive() || o instanceof String) { -075 set(field.getDeclaredAnnotations(), field, root); -076 System.out.println("prim"); -077 } else if (getCustom(o) != null) { -078 set(field.getDeclaredAnnotations(), getCustom(o)); -079 System.out.println("cust"); -080 } -081 } -082 } -083 } catch (IllegalAccessException ignored) { -084 System.out.println("reeeeeeeeeeeeeeeeeeee"); -085 } -086 } -087 for (Method m : root.getClass().getMethods()) { -088 set(m.getDeclaredAnnotations(), m, root); -089 } -090 } -091 -092 // TODO make list and do sort with comparators -093 // I wish this had a comment describing what Alex thinks it's doing, -094 // I *think* it'strying to set the 'indexed' entries to their preferred locations -095 // then filling in the gaps with unindexed or lower priority entries. -096 // That bottom loop is also quite slow, but we're talking about 0-20 entries, so performance -097 // is probably irrelevant... -098 private Entry<?>[] generate(Set<Entry<?>> a) { -099 Entry<?>[] returnEntry = new Entry[a.size()]; -100 List<Entry<?>> unindexed = new ArrayList<>(); -101 for (Entry<?> e : a) { -102 int index = e.getIndex(); -103 if (index >= 0 && index < returnEntry.length) { -104 Entry<?> other = returnEntry[index]; -105 if (other == null) { -106 returnEntry[index] = e; -107 } else { -108 if (e.getPriority() > other.getPriority()) { -109 unindexed.add(other); -110 returnEntry[index] = e; -111 } else { -112 unindexed.add(e); -113 } -114 } -115 } else { -116 unindexed.add(e); +006import com.technototes.library.logger.entry.NumberEntry; +007import com.technototes.library.logger.entry.StringEntry; +008import java.lang.annotation.Annotation; +009import java.lang.reflect.Field; +010import java.lang.reflect.InvocationTargetException; +011import java.lang.reflect.Method; +012import java.util.ArrayList; +013import java.util.Arrays; +014import java.util.LinkedHashSet; +015import java.util.List; +016import java.util.Set; +017import java.util.function.BooleanSupplier; +018import java.util.function.DoubleSupplier; +019import java.util.function.IntSupplier; +020import java.util.function.Supplier; +021import org.firstinspires.ftc.robotcore.external.Telemetry; +022 +023/** +024 * The class to manage logging +025 * +026 * @author Alex Stedman +027 */ +028public class Logger { +029 +030 public Entry<?>[] runEntries; +031 public Entry<?>[] initEntries; +032 private final Set<Entry<?>> unindexedRunEntries; +033 private final Set<Entry<?>> unindexedInitEntries; +034 private final Telemetry telemetry; +035 private final OpMode opMode; +036 /** +037 * The divider between the tag and the entry for telemetry (default ':') +038 */ +039 public char captionDivider = ':'; +040 +041 /** +042 * Instantiate the logger +043 * +044 * @param op The OpMode class +045 */ +046 public Logger(OpMode op) { +047 opMode = op; +048 telemetry = op.telemetry; +049 telemetry.setDisplayFormat(Telemetry.DisplayFormat.HTML); +050 unindexedRunEntries = new LinkedHashSet<>(); +051 unindexedInitEntries = new LinkedHashSet<>(); +052 configure(op); +053 runEntries = generate(unindexedRunEntries); +054 initEntries = generate(unindexedInitEntries); +055 } +056 +057 private void configure(Object root) { +058 for (Field field : root.getClass().getFields()) { +059 try { +060 Object o = field.get(root); +061 if (isFieldAllowed(field)) { +062 if (o instanceof Loggable) { +063 configure(o); +064 } else if ( +065 field.isAnnotationPresent(Log.class) || +066 field.isAnnotationPresent(Log.Number.class) || +067 field.isAnnotationPresent(Log.Boolean.class) +068 ) { +069 if (field.getType().isPrimitive() || o instanceof String) { +070 set(field.getDeclaredAnnotations(), field, root); +071 System.out.println("prim"); +072 } else if (getCustom(o) != null) { +073 set(field.getDeclaredAnnotations(), getCustom(o)); +074 System.out.println("cust"); +075 } +076 } +077 } +078 } catch (IllegalAccessException ignored) { +079 System.out.println("reeeeeeeeeeeeeeeeeeee"); +080 } +081 } +082 for (Method m : root.getClass().getMethods()) { +083 set(m.getDeclaredAnnotations(), m, root); +084 } +085 } +086 +087 // TODO make list and do sort with comparators +088 // I wish this had a comment describing what Alex thinks it's doing, +089 // I *think* it'strying to set the 'indexed' entries to their preferred locations +090 // then filling in the gaps with unindexed or lower priority entries. +091 // That bottom loop is also quite slow, but we're talking about 0-20 entries, so performance +092 // is probably irrelevant... +093 private Entry<?>[] generate(Set<Entry<?>> a) { +094 Entry<?>[] returnEntry = new Entry[a.size()]; +095 List<Entry<?>> unindexed = new ArrayList<>(); +096 for (Entry<?> e : a) { +097 int index = e.getIndex(); +098 if (index >= 0 && index < returnEntry.length) { +099 Entry<?> other = returnEntry[index]; +100 if (other == null) { +101 returnEntry[index] = e; +102 } else { +103 if (e.getPriority() > other.getPriority()) { +104 unindexed.add(other); +105 returnEntry[index] = e; +106 } else { +107 unindexed.add(e); +108 } +109 } +110 } else { +111 unindexed.add(e); +112 } +113 } +114 for (int i = 0; unindexed.size() > 0; i++) { +115 if (returnEntry[i] == null) { +116 returnEntry[i] = unindexed.remove(0); 117 } 118 } -119 for (int i = 0; unindexed.size() > 0; i++) { -120 if (returnEntry[i] == null) { -121 returnEntry[i] = unindexed.remove(0); -122 } -123 } -124 return returnEntry; -125 } -126 -127 private void update(Entry<?>[] choice) { -128 try { -129 for (int i = 0; i < choice.length; i++) { -130 telemetry.addLine( -131 (i > 9 ? i + "| " : i + " | ") + -132 (choice[i] == null ? "" : choice[i].getTag().replace('`', captionDivider) + choice[i].toString()) -133 ); -134 } -135 telemetry.update(); -136 } catch (Exception ignored) {} -137 } -138 -139 /** -140 * Update the logged run items in temeletry -141 */ -142 public void runUpdate() { -143 update(runEntries); -144 } -145 -146 /** -147 * Update the logged init items in temeletry -148 */ -149 public void initUpdate() { -150 update(initEntries); -151 } -152 -153 private void set(Annotation[] a, Method m, Object root) { -154 set( -155 a, -156 () -> { -157 try { -158 return m.invoke(root); -159 } catch (IllegalAccessException | InvocationTargetException e) { -160 e.printStackTrace(); -161 } -162 return null; -163 } -164 ); -165 } -166 -167 private void set(Annotation[] a, Field m, Object root) { -168 set( -169 a, -170 () -> { -171 try { -172 return m.get(root); -173 } catch (IllegalAccessException e) { -174 e.printStackTrace(); -175 } -176 return null; -177 } -178 ); -179 } -180 -181 @SuppressWarnings({ "unchecked" }) -182 private void set(Annotation[] a, Supplier<?> m) { -183 boolean init = false, run = true; -184 Entry<?> e = null; -185 for (Annotation as : a) { -186 if (as instanceof Log.NumberSlider) { -187 e = -188 new NumberSliderEntry( -189 ((Log.NumberSlider) as).name(), -190 (Supplier<Number>) m, -191 ((Log.NumberSlider) as).index(), -192 ((Log.NumberSlider) as).min(), -193 ((Log.NumberSlider) as).max(), -194 ((Log.NumberSlider) as).scale(), -195 ((Log.NumberSlider) as).color(), -196 ((Log.NumberSlider) as).sliderBackground(), -197 ((Log.NumberSlider) as).outline(), -198 ((Log.NumberSlider) as).slider() -199 ); -200 e.setPriority(((Log.NumberSlider) as).priority()); -201 } else if (as instanceof Log.NumberBar) { -202 e = -203 new NumberBarEntry( -204 ((Log.NumberBar) as).name(), -205 (Supplier<Number>) m, -206 ((Log.NumberBar) as).index(), -207 ((Log.NumberBar) as).min(), -208 ((Log.NumberBar) as).max(), -209 ((Log.NumberBar) as).scale(), -210 ((Log.NumberBar) as).color(), -211 ((Log.NumberBar) as).completeBarColor(), -212 ((Log.NumberBar) as).outline(), -213 ((Log.NumberBar) as).incompleteBarColor() -214 ); -215 e.setPriority(((Log.NumberBar) as).priority()); -216 } else if (as instanceof Log.Number) { -217 e = -218 new NumberEntry( -219 ((Log.Number) as).name(), -220 (Supplier<Number>) m, -221 ((Log.Number) as).index(), -222 ((Log.Number) as).color(), -223 ((Log.Number) as).numberColor() -224 ); -225 e.setPriority(((Log.Number) as).priority()); -226 } else if (as instanceof Log) { -227 e = -228 new StringEntry( -229 ((Log) as).name(), -230 (Supplier<String>) m, -231 ((Log) as).index(), -232 ((Log) as).color(), -233 ((Log) as).format(), -234 ((Log) as).entryColor() -235 ); -236 e.setPriority(((Log) as).priority()); -237 } else if (as instanceof Log.Boolean) { -238 e = -239 new BooleanEntry( -240 ((Log.Boolean) as).name(), -241 (Supplier<Boolean>) m, -242 ((Log.Boolean) as).index(), -243 ((Log.Boolean) as).trueValue(), -244 ((Log.Boolean) as).falseValue(), -245 ((Log.Boolean) as).color(), -246 ((Log.Boolean) as).trueFormat(), -247 ((Log.Boolean) as).falseFormat(), -248 ((Log.Boolean) as).trueColor(), -249 ((Log.Boolean) as).falseColor() -250 ); -251 e.setPriority(((Log.Boolean) as).priority()); -252 } else if (as instanceof LogConfig.Run) { -253 init = ((LogConfig.Run) as).duringInit(); -254 run = ((LogConfig.Run) as).duringRun(); -255 } -256 } -257 if (e != null) { -258 if (init) { -259 unindexedInitEntries.add(e); -260 } -261 if (run) { -262 unindexedRunEntries.add(e); -263 } -264 } -265 } -266 -267 /** -268 * Repeat a String -269 * -270 * @param s The String to repeat -271 * @param num The amount of times to repeat the String -272 * @return The String s repeated num times -273 */ -274 public static String repeat(String s, int num) { -275 if (num > 100) { -276 System.err.println("One of the entries is too long, make sure your scaling is correct"); -277 num = 100; -278 } -279 return num > 0 ? repeat(s, num - 1) + s : ""; -280 } -281 -282 private static Supplier<?> getCustom(Object o) { -283 if (o instanceof Supplier) { -284 return (Supplier<?>) o; -285 } else if (o instanceof BooleanSupplier) { -286 return ((BooleanSupplier) o)::getAsBoolean; -287 } else if (o instanceof IntSupplier) { -288 return ((IntSupplier) o)::getAsInt; -289 } else if (o instanceof DoubleSupplier) { -290 return ((DoubleSupplier) o)::getAsDouble; -291 } else if (o instanceof Integer) { -292 return () -> (Integer) o; -293 } else if (o instanceof Double) { -294 return () -> (Double) o; -295 } else if (o instanceof Boolean) { -296 return () -> (Boolean) o; -297 } else { -298 return null; -299 } -300 } -301 -302 private boolean isFieldAllowed(Field f) { -303 if (f.isAnnotationPresent(LogConfig.Whitelist.class)) { -304 if (!Arrays.asList(f.getAnnotation(LogConfig.Whitelist.class).value()).contains(opMode.getClass())) { -305 return false; -306 } -307 } -308 if (f.isAnnotationPresent(LogConfig.Blacklist.class)) { -309 if (Arrays.asList(f.getAnnotation(LogConfig.Blacklist.class).value()).contains(opMode.getClass())) { -310 return false; -311 } -312 } -313 return !f.isAnnotationPresent(LogConfig.Disabled.class); -314 } -315} +119 return returnEntry; +120 } +121 +122 private void update(Entry<?>[] choice) { +123 try { +124 for (Entry<?> item : choice) { +125 // telemetry.addLine( +126 // (i > 9 ? i + "| " : i + " | ") + +127 // (choice[i] == null ? "" : choice[i].getTag().replace('`', captionDivider) + choice[i].toString()) +128 // ); +129 // All teh fancy HTML stuff gets in the way of the FTC Dashboard graph +130 telemetry.addData(item.getName(), item.get()); +131 } +132 telemetry.update(); +133 } catch (Exception ignored) {} +134 } +135 +136 /** +137 * Update the logged run items in temeletry +138 */ +139 public void runUpdate() { +140 update(runEntries); +141 } +142 +143 /** +144 * Update the logged init items in temeletry +145 */ +146 public void initUpdate() { +147 update(initEntries); +148 } +149 +150 private void set(Annotation[] a, Method m, Object root) { +151 set( +152 a, +153 () -> { +154 try { +155 return m.invoke(root); +156 } catch (IllegalAccessException | InvocationTargetException e) { +157 e.printStackTrace(); +158 } +159 return null; +160 } +161 ); +162 } +163 +164 private void set(Annotation[] a, Field m, Object root) { +165 set( +166 a, +167 () -> { +168 try { +169 return m.get(root); +170 } catch (IllegalAccessException e) { +171 e.printStackTrace(); +172 } +173 return null; +174 } +175 ); +176 } +177 +178 @SuppressWarnings({ "unchecked" }) +179 private void set(Annotation[] a, Supplier<?> m) { +180 boolean init = false, run = true; +181 Entry<?> e = null; +182 for (Annotation as : a) { +183 if (as instanceof Log.Number) { +184 e = +185 new NumberEntry( +186 ((Log.Number) as).name(), +187 (Supplier<Number>) m, +188 ((Log.Number) as).index() +189 ); +190 e.setPriority(((Log.Number) as).priority()); +191 } else if (as instanceof Log) { +192 e = +193 new StringEntry( +194 ((Log) as).name(), +195 (Supplier<String>) m, +196 ((Log) as).index(), +197 ((Log) as).format() +198 ); +199 e.setPriority(((Log) as).priority()); +200 } else if (as instanceof Log.Boolean) { +201 e = +202 new BooleanEntry( +203 ((Log.Boolean) as).name(), +204 (Supplier<Boolean>) m, +205 ((Log.Boolean) as).index(), +206 ((Log.Boolean) as).trueValue(), +207 ((Log.Boolean) as).falseValue() +208 ); +209 e.setPriority(((Log.Boolean) as).priority()); +210 } else if (as instanceof LogConfig.Run) { +211 init = ((LogConfig.Run) as).duringInit(); +212 run = ((LogConfig.Run) as).duringRun(); +213 } +214 } +215 if (e != null) { +216 if (init) { +217 unindexedInitEntries.add(e); +218 } +219 if (run) { +220 unindexedRunEntries.add(e); +221 } +222 } +223 } +224 +225 /** +226 * Repeat a String +227 * +228 * @param s The String to repeat +229 * @param num The amount of times to repeat the String +230 * @return The String s repeated num times +231 */ +232 public static String repeat(String s, int num) { +233 if (num > 100) { +234 System.err.println("One of the entries is too long, make sure your scaling is correct"); +235 num = 100; +236 } +237 return num > 0 ? repeat(s, num - 1) + s : ""; +238 } +239 +240 private static Supplier<?> getCustom(Object o) { +241 if (o instanceof Supplier) { +242 return (Supplier<?>) o; +243 } else if (o instanceof BooleanSupplier) { +244 return ((BooleanSupplier) o)::getAsBoolean; +245 } else if (o instanceof IntSupplier) { +246 return ((IntSupplier) o)::getAsInt; +247 } else if (o instanceof DoubleSupplier) { +248 return ((DoubleSupplier) o)::getAsDouble; +249 } else if (o instanceof Integer) { +250 return () -> (Integer) o; +251 } else if (o instanceof Double) { +252 return () -> (Double) o; +253 } else if (o instanceof Boolean) { +254 return () -> (Boolean) o; +255 } else { +256 return null; +257 } +258 } +259 +260 private boolean isFieldAllowed(Field f) { +261 if (f.isAnnotationPresent(LogConfig.AllowList.class)) { +262 if (!Arrays.asList(f.getAnnotation(LogConfig.AllowList.class).value()).contains(opMode.getClass())) { +263 return false; +264 } +265 } +266 if (f.isAnnotationPresent(LogConfig.DenyList.class)) { +267 if (Arrays.asList(f.getAnnotation(LogConfig.DenyList.class).value()).contains(opMode.getClass())) { +268 return false; +269 } +270 } +271 return !f.isAnnotationPresent(LogConfig.Disabled.class); +272 } +273} diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/BooleanEntry.html b/docs/TechnoLib/src-html/com/technototes/library/logger/entry/BooleanEntry.html index ef1975ae..fdf389e0 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/BooleanEntry.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/entry/BooleanEntry.html @@ -18,30 +18,25 @@ 005 006public class BooleanEntry extends Entry<Boolean> { 007 -008 private StringEntry trueEntry, falseEntry; +008 private String trueEntry, falseEntry; 009 010 public BooleanEntry( 011 String n, 012 Supplier<Boolean> s, 013 int index, 014 String wt, -015 String wf, -016 Color c, -017 String tf, -018 String ff, -019 Color tc, -020 Color fc -021 ) { -022 super(n, s, index, c); -023 trueEntry = new StringEntry("", () -> wt, -1, Color.NO_COLOR, tf, tc); -024 falseEntry = new StringEntry("", () -> wf, -1, Color.NO_COLOR, ff, fc); +015 String wf +016 ) { +017 super(n, s, index); +018 trueEntry = wt; +019 falseEntry = wf; +020 } +021 +022 @Override +023 public String toString() { +024 return (get() ? trueEntry : falseEntry); 025 } -026 -027 @Override -028 public String toString() { -029 return (get() ? trueEntry : falseEntry).get(); -030 } -031} +026} diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/Entry.html b/docs/TechnoLib/src-html/com/technototes/library/logger/entry/Entry.html index 88f035c8..86b7e984 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/Entry.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/entry/Entry.html @@ -13,131 +13,110 @@
    001package com.technototes.library.logger.entry;
     002
    -003import com.technototes.library.util.Color;
    -004import java.util.function.Supplier;
    -005
    -006/**
    -007 * The root class for logging entries
    -008 *
    -009 * @param <T> The type of value being stored by the entry
    -010 * @author Alex Stedman
    -011 */
    -012public abstract class Entry<T> implements Supplier<T> {
    -013
    -014    /**
    -015     * The index (in the list) of the entry
    -016     */
    -017    protected int x;
    -018    /**
    -019     * The priority (in the telemetry list) of the entry
    -020     */
    -021    protected int priority;
    -022    /**
    -023     * The function called to get the value to display
    -024     */
    -025    protected Supplier<T> supplier;
    -026    /**
    -027     * The name of the Entry
    -028     */
    -029    protected String name;
    +003import java.util.function.Supplier;
    +004
    +005/**
    +006 * The root class for logging entries
    +007 *
    +008 * @param <T> The type of value being stored by the entry
    +009 * @author Alex Stedman
    +010 */
    +011public abstract class Entry<T> implements Supplier<T> {
    +012
    +013    /**
    +014     * The index (in the list) of the entry
    +015     */
    +016    protected int x;
    +017    /**
    +018     * The priority (in the telemetry list) of the entry
    +019     */
    +020    protected int priority;
    +021    /**
    +022     * The function called to get the value to display
    +023     */
    +024    protected Supplier<T> supplier;
    +025    /**
    +026     * The name of the Entry
    +027     */
    +028    protected String name;
    +029
     030    /**
    -031     * String to use a 'header' (calculated from name and color)
    -032     */
    -033    protected String tag;
    -034    /**
    -035     * Color to display
    +031     * Create an entry with name, value, index
    +032     *
    +033     * @param n     Name of the entry
    +034     * @param s     Value function to display
    +035     * @param index Index of the entry
     036     */
    -037    protected Color color;
    -038
    -039    /**
    -040     * Create an entry with name, value, index, and color
    -041     *
    -042     * @param n     Name of the entry
    -043     * @param s     Value function to display
    -044     * @param index Index of the entry
    -045     * @param c     Color to display
    -046     */
    -047    public Entry(String n, Supplier<T> s, int index, Color c) {
    -048        x = index;
    -049        supplier = s;
    -050        name = n;
    -051        color = c;
    -052        tag = (name.equals("") ? " " : color.format(name) + " ` ");
    -053    }
    -054
    -055    /**
    -056     * Set's the priority for this log line (handy for telemetry overflow)
    -057     *
    -058     * @param p The priority
    -059     * @return Self (for chaining)
    -060     */
    -061    public Entry<T> setPriority(int p) {
    -062        priority = p;
    -063        return this;
    -064    }
    -065
    -066    @Override
    -067    public T get() {
    -068        return supplier.get();
    -069    }
    -070
    -071    /**
    -072     * The String for the logged item
    -073     *
    -074     * @return The String
    -075     */
    -076    @Override
    -077    public String toString() {
    -078        return supplier.get().toString();
    -079    }
    -080
    -081    /**
    -082     * The tag for the entry
    -083     *
    -084     * @return The tag
    -085     */
    -086    public String getTag() {
    -087        return tag;
    -088    }
    -089
    -090    /**
    -091     * Get the name (unformatted tag)
    -092     *
    -093     * @return The name
    -094     */
    -095    public String getName() {
    -096        return name;
    -097    }
    -098
    -099    /**
    -100     * Get the index for the entry
    -101     *
    -102     * @return The index
    -103     */
    -104    public int getIndex() {
    -105        return x;
    -106    }
    -107
    -108    /**
    -109     * Set index
    -110     *
    -111     * @param i New index
    -112     * @return this
    -113     */
    -114    public Entry setIndex(int i) {
    -115        x = i;
    -116        return this;
    -117    }
    -118
    -119    /**
    -120     * Get Priority for the entry
    -121     *
    -122     * @return The priority
    -123     */
    -124    public int getPriority() {
    -125        return priority;
    -126    }
    -127}
    +037    public Entry(String n, Supplier<T> s, int index) {
    +038        x = index;
    +039        supplier = s;
    +040        name = n;
    +041    }
    +042
    +043    /**
    +044     * Set's the priority for this log line (handy for telemetry overflow)
    +045     *
    +046     * @param p The priority
    +047     * @return Self (for chaining)
    +048     */
    +049    public Entry<T> setPriority(int p) {
    +050        priority = p;
    +051        return this;
    +052    }
    +053
    +054    @Override
    +055    public T get() {
    +056        return supplier.get();
    +057    }
    +058
    +059    /**
    +060     * The String for the logged item
    +061     *
    +062     * @return The String
    +063     */
    +064    @Override
    +065    public String toString() {
    +066        return supplier.get().toString();
    +067    }
    +068
    +069    /**
    +070     * Get the name
    +071     *
    +072     * @return The name
    +073     */
    +074    public String getName() {
    +075        return name;
    +076    }
    +077
    +078    /**
    +079     * Get the index for the entry
    +080     *
    +081     * @return The index
    +082     */
    +083    public int getIndex() {
    +084        return x;
    +085    }
    +086
    +087    /**
    +088     * Set index
    +089     *
    +090     * @param i New index
    +091     * @return this
    +092     */
    +093    public Entry setIndex(int i) {
    +094        x = i;
    +095        return this;
    +096    }
    +097
    +098    /**
    +099     * Get Priority for the entry
    +100     *
    +101     * @return The priority
    +102     */
    +103    public int getPriority() {
    +104        return priority;
    +105    }
    +106}
     
     
     
    diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/NumberBarEntry.html b/docs/TechnoLib/src-html/com/technototes/library/logger/entry/NumberBarEntry.html
    deleted file mode 100644
    index f570a936..00000000
    --- a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/NumberBarEntry.html
    +++ /dev/null
    @@ -1,113 +0,0 @@
    -
    -
    -
    -
    -Source code
    -
    -
    -
    -
    -
    -
    -
    -
    -
    001package com.technototes.library.logger.entry;
    -002
    -003import com.technototes.library.logger.Logger;
    -004import com.technototes.library.util.Color;
    -005import java.util.function.Supplier;
    -006
    -007public class NumberBarEntry extends NumberSliderEntry {
    -008
    -009    // primary is bar color, secondary is outline, tertiary is incomplete bar
    -010    public NumberBarEntry(
    -011        String n,
    -012        Supplier<Number> s,
    -013        int x,
    -014        Number mi,
    -015        Number ma,
    -016        Number sc,
    -017        Color c,
    -018        Color pri,
    -019        Color sec,
    -020        Color tert
    -021    ) {
    -022        super(n, s, x, mi, ma, sc, c, pri, sec, tert);
    -023    }
    -024
    -025    @Override
    -026    public String toString() {
    -027        StringBuilder r = new StringBuilder(secondary.format("["));
    -028        int totalAmt = (int) ((max() - min()) / scale());
    -029        int fullAmt = (int) (Math.round((getDouble() - min()) / scale()));
    -030        r.append(primary.format(Logger.repeat("█", fullAmt + 1)));
    -031        r.append(tertiary.format(Logger.repeat("━", totalAmt - fullAmt)));
    -032        r.append(secondary.format("]"));
    -033        return r.toString();
    -034    }
    -035}
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    - - diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/NumberEntry.html b/docs/TechnoLib/src-html/com/technototes/library/logger/entry/NumberEntry.html index 26d11f3e..994637e7 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/NumberEntry.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/entry/NumberEntry.html @@ -20,21 +20,16 @@ 007 008 protected Color numberColor; 009 -010 public NumberEntry(String n, Supplier<Number> s, int x, Color c, Color num) { -011 super(n, s, x, c); -012 numberColor = num; -013 } +010 public NumberEntry(String n, Supplier<Number> s, int x) { +011 super(n, s, x); +012 } +013 014 -015 public NumberEntry(String n, Supplier<Number> s, int x, Color c) { -016 super(n, s, x, c); -017 numberColor = Color.NO_COLOR; +015 @Override +016 public String toString() { +017 return numberColor.format(get()); 018 } -019 -020 @Override -021 public String toString() { -022 return numberColor.format(get()); -023 } -024} +019} diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/NumberSliderEntry.html b/docs/TechnoLib/src-html/com/technototes/library/logger/entry/NumberSliderEntry.html deleted file mode 100644 index ad0b866e..00000000 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/NumberSliderEntry.html +++ /dev/null @@ -1,138 +0,0 @@ - - - - -Source code - - - - - - -
    -
    -
    001package com.technototes.library.logger.entry;
    -002
    -003import com.technototes.library.logger.Logger;
    -004import com.technototes.library.util.Color;
    -005import java.util.function.Supplier;
    -006
    -007public class NumberSliderEntry extends NumberEntry {
    -008
    -009    protected Number min, max, scale;
    -010    protected Color primary, secondary, tertiary;
    -011
    -012    public NumberSliderEntry(
    -013        String n,
    -014        Supplier<Number> s,
    -015        int x,
    -016        Number mi,
    -017        Number ma,
    -018        Number sc,
    -019        Color c,
    -020        Color pr,
    -021        Color sec,
    -022        Color tert
    -023    ) {
    -024        super(n, s, x, c);
    -025        min = mi;
    -026        max = ma;
    -027        scale = sc;
    -028        primary = pr;
    -029        secondary = sec;
    -030        tertiary = tert;
    -031    }
    -032
    -033    public double min() {
    -034        return min.doubleValue();
    -035    }
    -036
    -037    public double max() {
    -038        return max.doubleValue();
    -039    }
    -040
    -041    public double scale() {
    -042        return scale.doubleValue();
    -043    }
    -044
    -045    public double getDouble() {
    -046        return get().doubleValue();
    -047    }
    -048
    -049    @Override
    -050    public String toString() {
    -051        StringBuilder r = new StringBuilder(secondary.format("["));
    -052        int totalAmt = (int) ((max() - min()) / scale());
    -053        int fullAmt = (int) (Math.round((getDouble() - min()) / scale()));
    -054        r.append(tertiary.format(Logger.repeat("━", fullAmt)));
    -055        r.append(primary.format("█"));
    -056        r.append(tertiary.format(Logger.repeat("━", totalAmt - fullAmt)));
    -057        r.append(secondary.format("]"));
    -058        return r.toString();
    -059    }
    -060}
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    -
    - - diff --git a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/StringEntry.html b/docs/TechnoLib/src-html/com/technototes/library/logger/entry/StringEntry.html index ce76bd07..6d7f5d67 100644 --- a/docs/TechnoLib/src-html/com/technototes/library/logger/entry/StringEntry.html +++ b/docs/TechnoLib/src-html/com/technototes/library/logger/entry/StringEntry.html @@ -13,25 +13,22 @@
    001package com.technototes.library.logger.entry;
     002
    -003import com.technototes.library.util.Color;
    -004import java.util.function.Supplier;
    -005
    -006public class StringEntry extends Entry<String> {
    -007
    -008    private String format;
    -009    private Color entryColor;
    -010
    -011    public StringEntry(String n, Supplier<String> s, int x, Color c, String f, Color ec) {
    -012        super(n, s, x, c);
    -013        format = f;
    -014        entryColor = ec;
    -015    }
    -016
    -017    @Override
    -018    public String toString() {
    -019        return entryColor.format(format, get());
    -020    }
    -021}
    +003import java.util.function.Supplier;
    +004
    +005public class StringEntry extends Entry<String> {
    +006
    +007    private String format;
    +008
    +009    public StringEntry(String n, Supplier<String> s, int x, String f) {
    +010        super(n, s, x);
    +011        format = f;
    +012    }
    +013
    +014    @Override
    +015    public String toString() {
    +016        return String.format(format, get());
    +017    }
    +018}
     
     
     
    diff --git a/docs/TechnoLib/type-search-index.js b/docs/TechnoLib/type-search-index.js
    index c88a966d..584356d1 100644
    --- a/docs/TechnoLib/type-search-index.js
    +++ b/docs/TechnoLib/type-search-index.js
    @@ -1,6 +1,7 @@
     typeSearchIndex = [
       { l: 'All Classes and Interfaces', u: 'allclasses-index.html' },
       { p: 'com.technototes.library.util', l: 'Alliance' },
    +  { p: 'com.technototes.library.logger', l: 'LogConfig.AllowList' },
       { p: 'com.technototes.library.hardware2', l: 'AnalogBuilder' },
       { p: 'com.technototes.library.hardware.sensor', l: 'AnalogSensor' },
       { p: 'com.technototes.library.hardware.sensor', l: 'IMU.AxesSigns' },
    @@ -8,7 +9,6 @@ typeSearchIndex = [
       { p: 'com.technototes.library.control', l: 'GamepadBase.Axis' },
       { p: 'com.technototes.library.control', l: 'AxisBase' },
       { p: 'com.technototes.library.control', l: 'Binding' },
    -  { p: 'com.technototes.library.logger', l: 'LogConfig.Blacklist' },
       { p: 'com.technototes.library.util', l: 'Alliance.Blue' },
       { p: 'com.technototes.library.logger', l: 'Log.Boolean' },
       { p: 'com.technototes.library.logger.entry', l: 'BooleanEntry' },
    @@ -35,6 +35,7 @@ typeSearchIndex = [
       { p: 'com.technototes.library.command', l: 'ConditionalCommand' },
       { p: 'com.technototes.library.hardware.servo', l: 'ServoProfiler.Constraints' },
       { p: 'com.technototes.library.hardware2', l: 'CRServoBuilder' },
    +  { p: 'com.technototes.library.logger', l: 'LogConfig.DenyList' },
       { p: 'com.technototes.library.subsystem', l: 'DeviceSubsystem' },
       { p: 'com.technototes.library.util', l: 'Differential' },
       { p: 'com.technototes.library.util', l: 'Differential.DifferentialPriority' },
    @@ -80,11 +81,7 @@ typeSearchIndex = [
       { p: 'com.technototes.library.hardware.motor', l: 'MotorGroup' },
       { p: 'com.technototes.library.subsystem.motor', l: 'MotorSubsystem' },
       { p: 'com.technototes.library.logger', l: 'Log.Number' },
    -  { p: 'com.technototes.library.logger', l: 'Log.NumberBar' },
    -  { p: 'com.technototes.library.logger.entry', l: 'NumberBarEntry' },
       { p: 'com.technototes.library.logger.entry', l: 'NumberEntry' },
    -  { p: 'com.technototes.library.logger', l: 'Log.NumberSlider' },
    -  { p: 'com.technototes.library.logger.entry', l: 'NumberSliderEntry' },
       { p: 'com.technototes.library.structure', l: 'CommandOpMode.OpModeState' },
       { p: 'com.technototes.library.command', l: 'ParallelCommandGroup' },
       { p: 'com.technototes.library.command', l: 'ParallelDeadlineGroup' },
    @@ -113,6 +110,5 @@ typeSearchIndex = [
       { p: 'com.technototes.library.subsystem.drivebase', l: 'TankDrivebaseSubsystem' },
       { p: 'com.technototes.library.control', l: 'Binding.Type' },
       { p: 'com.technototes.library.command', l: 'WaitCommand' },
    -  { p: 'com.technototes.library.logger', l: 'LogConfig.Whitelist' },
     ];
     updateSearchResults();
    diff --git a/notes.md b/notes.md
    index d917ab77..049c1152 100644
    --- a/notes.md
    +++ b/notes.md
    @@ -1,6 +1,7 @@
     # Notes for Kevin
     
    -(I'm the software mentor, picking up ownership of TechnLib from Alex Stedman, the original author)
    +(I'm the software mentor for 16750/20403 and have picked up ownership of TechnLib from Alex Stedman,
    +the original author, as he's doing silly things like "attending college")
     
     ## Hardware details to keep in mind
     
    @@ -9,3 +10,40 @@ The analog sticks are vertically inverted: When you push the stick up/away, the
     The shoulder triggers' range is from 0 to 1, not -1 to 1.
     
     I'm not currently sure what orientation the SDK 8.1+ IMU calls 0 degrees.
    +
    +## Simulation
    +
    +This has been in my head since my first year (2019, SkyStone)
    +
    +There ought to be a simulator for this stuff. It would let programmers work more independently to
    +validate basic stuff. I've never built a simulator, but I'm a semi competent developer, so (famous
    +last words) how hard can it be? ftcsim and vrs both lack some amount of flexibility, why doing a lot
    +more than what I really need/want for a team who's building a real bot.
    +
    +The core things that would need simulated:
    +
    +- Motors (with encoders)
    +- Servos (in both CR and Servo mode)
    +- Sensors (pick the order to get them going)
    +  - IMU
    +  - Bump
    +  - Color
    +  - 2M range
    +  - Range
    +
    +Probably not worth simulating:
    +
    +- Vision. I could support connecting a webcam so the students could use an actual webcam, but I'm
    +  not about to deal with AprilTags and TFOD. ML sucks. It doesn't work at level level of determinism
    +  that makes me thing I could do anything useful with it. It's quantum physics, if the probability
    +  of weird stuff happening is 10^-2 instead of 10^-20000000. Thanks, but no thanks.
    +- Controllers. Just wire them up from the computer
    +
    +Where do things get messy? I'd need some mechanism to translate rotational motion. I don't have the
    +interest to do a full physics simulator, so I could potentially make this pretty rudimentary.
    +
    +### What's next?
    +
    +Get through this season, then maybe start horsing around with this? Maybe learn Kotlin, since it
    +looks _much_ less verbose than Java (Seriously, Java, you've had almost 30 years. Why do you still
    +hate developers so much?)
    diff --git a/package.json b/package.json
    index 123f70a8..d68dbeff 100644
    --- a/package.json
    +++ b/package.json
    @@ -1,6 +1,6 @@
     {
       "name": "technolib",
    -  "version": "1.0.0",
    +  "version": "1.3.1",
       "description": "TechnoLib automation scripts",
       "main": "build/automation.js",
       "repository": "https://github.com/technototes/TechnoLib.git",
    diff --git a/readme.md b/readme.md
    index e4f40b11..89ef362b 100644
    --- a/readme.md
    +++ b/readme.md
    @@ -4,14 +4,12 @@ TechnoLib is a FTC Library for everyone:
     
     - WPILib inspired command structure
     - Tons of simple implementations to provide abstractions, and teach you the basics
    -- EOCV integration for vision
    -- RoadRunner integration for pathfollowing
    +- EasyOpenCV integration for vision
    +- RoadRunner integration for path-following
     - Annotation based Telemetry
     - And much much more
     
    -**The goal of this library is stated as follows** The goal of TechnoLib is not only to provide
    -versatile resources that assist in software development and strengthen code structure, but to also
    -abstract out redundancy.
    +### The goal of this library is not only to provide versatile resources that assist in software development and strengthen code structure, but to also abstract out redundancy.
     
     ## Installation
     
    @@ -25,11 +23,11 @@ But if this library is so good, it must be hard to install right? wrong:
          }
       ```
     - And add this to the dependencies block in TeamCode/build.gradle:
    -  `implementation 'com.github.technototes:TechnoLib:1.2.0'` **(replace 1.2.0 with the latest
    +  `implementation 'com.github.technototes:TechnoLib:1.3.0'` **(replace 1.3.0 with the latest
       release)**
     - Build the code and you are good to go
     
    -### Version 1.2.0 has breaking changes.
    +### Both versions 1.2.0 and 1.2.0 have breaking changes.
     
     See below for details
     
    @@ -81,3 +79,41 @@ to use the remapAxes function (which has been renamed) and the constructor for t
     that you specify the orientation of your control hub. The SDK also changed the axes' orientation on
     the hub. You'll be happier by just switching your mental model to the new IMU class (but it's weird
     that FIRST changed it :/ )
    +
    +# Notes from Kevin Frei
    +
    +Hi, the original author of this libary (Alex Stedman) graduated and went off to college. So now I'm
    +maintaining it.
    +
    +I'm an FTC mentor, not an FRC mentor. My goals are to enable capable programmers (often times coming
    +from Python) to be able to create a functional, _reliable_ robot quickly and easily. Java, and
    +particularly some Java conventions however, are not always the most conducive language to these
    +goals. I've made a few minor edits/improvements in the 1.3.0 release, but I'm also prototyping a new
    +2.0 release during the 2023/2024 season (our students are still using 1.3.0). The point of me
    +working on the prototype during build/competition season is primarily because I'm watching what
    +students struggle with, what I'm stuck explaining over & over, etc... and am trying to adjust
    +the library to be more approachable and easier to interact with.
    +
    +## Small Ideas
    +
    +Initially, I found the hardware wrapper types to be mostly just a waste of effort. Now, however, I'm
    +considering building out MUCH more capability in them. The 2 primary things I'd like to add are:
    +
    +1. Resilience to disconnected hardware
    +2. Easy, code-free logging opt-in/opt-out
    +
    +For item 1, we have a typical setup where we have flags in the "robot" object where we can
    +'disconnect' a subsystem, thus allowing the bot to continue to function even when specific hardware
    +isn't connected. This could be done without too much effort, and could potentially also be a nice
    +stepping stone to some level of hardware simulation.
    +
    +For item 2, for most of the hardware types, it's often useful to log data from those types (current
    +power/velocity, current tick values, etc...) but doing so is somewhat clunky. It would be nice if
    +you could set a flag in the dashboard, or perhaps just add a top-level to the constructor or a
    +subsystem that would enable/disable logging with little-to-no code changes.
    +
    +## Big Ideas
    +
    +Full simulation of a robot would be _tremendously_ helpful. Initially just being able to simulate
    +all the hardware would be useful. Being able to configure motors, servos, and sensors in a 3
    +dimensional model, with connections to parts would be MUCH more work (but also MUCH cooler)