From 6c0429c263829b1b7174333002fa8f498c4a3c09 Mon Sep 17 00:00:00 2001 From: Christopher Mahoney Date: Tue, 16 Jul 2024 15:39:24 -0400 Subject: [PATCH 01/10] [wpimath] Remove WheelPositions interface/concept (#6771) --- .../DifferentialDriveKinematics.java | 5 +---- .../DifferentialDriveWheelPositions.java | 8 ++----- .../kinematics/MecanumDriveKinematics.java | 7 +------ .../MecanumDriveWheelPositions.java | 9 ++------ .../first/math/kinematics/WheelPositions.java | 21 ------------------- .../include/frc/estimator/PoseEstimator.h | 1 - .../kinematics/DifferentialDriveKinematics.h | 3 +-- .../frc/kinematics/MecanumDriveKinematics.h | 5 +---- .../native/include/frc/kinematics/Odometry.h | 1 - .../include/frc/kinematics/WheelPositions.h | 15 ------------- 10 files changed, 8 insertions(+), 67 deletions(-) delete mode 100644 wpimath/src/main/java/edu/wpi/first/math/kinematics/WheelPositions.java delete mode 100644 wpimath/src/main/native/include/frc/kinematics/WheelPositions.h diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java index d67a7816475..c8a443904f6 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java @@ -8,7 +8,6 @@ import edu.wpi.first.math.MathSharedStore; import edu.wpi.first.math.MathUsageId; -import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Twist2d; import edu.wpi.first.math.kinematics.proto.DifferentialDriveKinematicsProto; import edu.wpi.first.math.kinematics.struct.DifferentialDriveKinematicsStruct; @@ -132,8 +131,6 @@ public DifferentialDriveWheelPositions interpolate( DifferentialDriveWheelPositions startValue, DifferentialDriveWheelPositions endValue, double t) { - return new DifferentialDriveWheelPositions( - MathUtil.interpolate(startValue.leftMeters, endValue.leftMeters, t), - MathUtil.interpolate(startValue.rightMeters, endValue.rightMeters, t)); + return startValue.interpolate(endValue, t); } } diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelPositions.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelPositions.java index ef4e5b0e92b..d97285f646b 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelPositions.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelPositions.java @@ -7,6 +7,7 @@ import static edu.wpi.first.units.Units.Meters; import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.interpolation.Interpolatable; import edu.wpi.first.math.kinematics.proto.DifferentialDriveWheelPositionsProto; import edu.wpi.first.math.kinematics.struct.DifferentialDriveWheelPositionsStruct; import edu.wpi.first.units.Distance; @@ -15,7 +16,7 @@ /** Represents the wheel positions for a differential drive drivetrain. */ public class DifferentialDriveWheelPositions - implements WheelPositions { + implements Interpolatable { /** Distance measured by the left side. */ public double leftMeters; @@ -69,11 +70,6 @@ public String toString() { "DifferentialDriveWheelPositions(Left: %.2f m, Right: %.2f m", leftMeters, rightMeters); } - @Override - public DifferentialDriveWheelPositions copy() { - return new DifferentialDriveWheelPositions(leftMeters, rightMeters); - } - @Override public DifferentialDriveWheelPositions interpolate( DifferentialDriveWheelPositions endValue, double t) { diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java index 26108088c63..0135af24d61 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java @@ -6,7 +6,6 @@ import edu.wpi.first.math.MathSharedStore; import edu.wpi.first.math.MathUsageId; -import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.geometry.Twist2d; import edu.wpi.first.math.kinematics.proto.MecanumDriveKinematicsProto; @@ -277,10 +276,6 @@ public void copyInto(MecanumDriveWheelPositions positions, MecanumDriveWheelPosi @Override public MecanumDriveWheelPositions interpolate( MecanumDriveWheelPositions startValue, MecanumDriveWheelPositions endValue, double t) { - return new MecanumDriveWheelPositions( - MathUtil.interpolate(startValue.frontLeftMeters, endValue.frontLeftMeters, t), - MathUtil.interpolate(startValue.frontRightMeters, endValue.frontRightMeters, t), - MathUtil.interpolate(startValue.rearLeftMeters, endValue.rearLeftMeters, t), - MathUtil.interpolate(startValue.rearRightMeters, endValue.rearRightMeters, t)); + return startValue.interpolate(endValue, t); } } diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java index e193dbdc4b4..1dc14a82928 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java @@ -7,6 +7,7 @@ import static edu.wpi.first.units.Units.Meters; import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.interpolation.Interpolatable; import edu.wpi.first.math.kinematics.proto.MecanumDriveWheelPositionsProto; import edu.wpi.first.math.kinematics.struct.MecanumDriveWheelPositionsStruct; import edu.wpi.first.units.Distance; @@ -17,7 +18,7 @@ /** Represents the wheel positions for a mecanum drive drivetrain. */ public class MecanumDriveWheelPositions - implements WheelPositions, + implements Interpolatable, ProtobufSerializable, StructSerializable { /** Distance measured by the front left wheel. */ @@ -99,12 +100,6 @@ public String toString() { frontLeftMeters, frontRightMeters, rearLeftMeters, rearRightMeters); } - @Override - public MecanumDriveWheelPositions copy() { - return new MecanumDriveWheelPositions( - frontLeftMeters, frontRightMeters, rearLeftMeters, rearRightMeters); - } - @Override public MecanumDriveWheelPositions interpolate(MecanumDriveWheelPositions endValue, double t) { return new MecanumDriveWheelPositions( diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/WheelPositions.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/WheelPositions.java deleted file mode 100644 index c0167e3e866..00000000000 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/WheelPositions.java +++ /dev/null @@ -1,21 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package edu.wpi.first.math.kinematics; - -import edu.wpi.first.math.interpolation.Interpolatable; - -/** - * Interface for wheel positions. - * - * @param Wheel positions type. - */ -public interface WheelPositions> extends Interpolatable { - /** - * Returns a copy of this instance. - * - * @return A copy. - */ - T copy(); -} diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h index da9f4f3ee68..f75a5afec73 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h @@ -19,7 +19,6 @@ #include "frc/interpolation/TimeInterpolatableBuffer.h" #include "frc/kinematics/Kinematics.h" #include "frc/kinematics/Odometry.h" -#include "frc/kinematics/WheelPositions.h" #include "units/time.h" #include "wpimath/MathShared.h" diff --git a/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h b/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h index a1be448c7bb..fbbb519182f 100644 --- a/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h @@ -91,8 +91,7 @@ class WPILIB_DLLEXPORT DifferentialDriveKinematics DifferentialDriveWheelPositions Interpolate( const DifferentialDriveWheelPositions& start, const DifferentialDriveWheelPositions& end, double t) const override { - return {wpi::Lerp(start.left, end.left, t), - wpi::Lerp(start.right, end.right, t)}; + return start.Interpolate(end, t); } /// Differential drive trackwidth. diff --git a/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h b/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h index 6c3d664496c..218908fd31a 100644 --- a/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h @@ -169,10 +169,7 @@ class WPILIB_DLLEXPORT MecanumDriveKinematics MecanumDriveWheelPositions Interpolate( const MecanumDriveWheelPositions& start, const MecanumDriveWheelPositions& end, double t) const override { - return {wpi::Lerp(start.frontLeft, end.frontLeft, t), - wpi::Lerp(start.frontRight, end.frontRight, t), - wpi::Lerp(start.rearLeft, end.rearLeft, t), - wpi::Lerp(start.rearRight, end.rearRight, t)}; + return start.Interpolate(end, t); } private: diff --git a/wpimath/src/main/native/include/frc/kinematics/Odometry.h b/wpimath/src/main/native/include/frc/kinematics/Odometry.h index c0daea0e3e0..e5a8e0f618e 100644 --- a/wpimath/src/main/native/include/frc/kinematics/Odometry.h +++ b/wpimath/src/main/native/include/frc/kinematics/Odometry.h @@ -10,7 +10,6 @@ #include "frc/geometry/Rotation2d.h" #include "frc/geometry/Translation2d.h" #include "frc/kinematics/Kinematics.h" -#include "frc/kinematics/WheelPositions.h" namespace frc { /** diff --git a/wpimath/src/main/native/include/frc/kinematics/WheelPositions.h b/wpimath/src/main/native/include/frc/kinematics/WheelPositions.h deleted file mode 100644 index 8867f6662a6..00000000000 --- a/wpimath/src/main/native/include/frc/kinematics/WheelPositions.h +++ /dev/null @@ -1,15 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include - -namespace frc { -template -concept WheelPositions = - std::copy_constructible && requires(T a, T b, double t) { - { a.Interpolate(b, t) } -> std::convertible_to; - }; -} // namespace frc From 8f60dc736deb105ea7b79678eaa2211cf744dd16 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 16 Jul 2024 13:40:06 -0700 Subject: [PATCH 02/10] [wpimath] Fix build by removing a bad #include (#6843) WheelPositions.h was removed in #6771. --- wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc | 1 - 1 file changed, 1 deletion(-) diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc index cb39dd26053..fb583226e40 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc @@ -7,7 +7,6 @@ #include "frc/estimator/PoseEstimator.h" #include "frc/geometry/Pose2d.h" #include "frc/geometry/Translation2d.h" -#include "frc/kinematics/WheelPositions.h" namespace frc { From f9d32ad706b06bdc2e24b2ba2143bb98268b318d Mon Sep 17 00:00:00 2001 From: Matt Date: Tue, 16 Jul 2024 16:40:36 -0400 Subject: [PATCH 03/10] [wpiutil] Struct: Remove explicit span length from int8 (#6840) --- wpiutil/src/main/native/include/wpi/struct/Struct.h | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/wpiutil/src/main/native/include/wpi/struct/Struct.h b/wpiutil/src/main/native/include/wpi/struct/Struct.h index 085b50bb345..f46d8dc50b8 100644 --- a/wpiutil/src/main/native/include/wpi/struct/Struct.h +++ b/wpiutil/src/main/native/include/wpi/struct/Struct.h @@ -478,10 +478,8 @@ struct Struct { static constexpr std::string_view GetTypeString() { return "struct:int8"; } static constexpr size_t GetSize() { return 1; } static constexpr std::string_view GetSchema() { return "int8 value"; } - static int8_t Unpack(std::span data) { return data[0]; } - static void Pack(std::span data, int8_t value) { - data[0] = value; - } + static int8_t Unpack(std::span data) { return data[0]; } + static void Pack(std::span data, int8_t value) { data[0] = value; } }; /** From 5f261a88afd499a7b16ada419ca7fd9faaee2f99 Mon Sep 17 00:00:00 2001 From: Joseph Eng <91924258+KangarooKoala@users.noreply.github.com> Date: Tue, 16 Jul 2024 17:20:07 -0700 Subject: [PATCH 04/10] [upstream_utils] Rework upstream_utils scripts (#6829) --- .github/workflows/upstream-utils.yml | 55 ++- upstream_utils/README.md | 81 +--- upstream_utils/{update_eigen.py => eigen.py} | 38 +- .../{update_expected.py => expected.py} | 24 +- upstream_utils/{update_fmt.py => fmt.py} | 21 +- upstream_utils/{update_gcem.py => gcem.py} | 27 +- upstream_utils/{update_json.py => json.py} | 43 +- upstream_utils/{update_libuv.py => libuv.py} | 43 +- upstream_utils/{update_llvm.py => llvm.py} | 32 +- .../{update_memory.py => memory.py} | 17 +- upstream_utils/{update_mpack.py => mpack.py} | 34 +- .../{update_protobuf.py => protobuf.py} | 50 ++- .../{update_sleipnir.py => sleipnir.py} | 42 +- ...update_stack_walker.py => stack_walker.py} | 54 +-- upstream_utils/upstream_utils.py | 410 ++++++++++++++++++ 15 files changed, 697 insertions(+), 274 deletions(-) rename upstream_utils/{update_eigen.py => eigen.py} (87%) rename upstream_utils/{update_expected.py => expected.py} (69%) rename upstream_utils/{update_fmt.py => fmt.py} (80%) rename upstream_utils/{update_gcem.py => gcem.py} (76%) rename upstream_utils/{update_json.py => json.py} (78%) rename upstream_utils/{update_libuv.py => libuv.py} (86%) rename upstream_utils/{update_llvm.py => llvm.py} (96%) rename upstream_utils/{update_memory.py => memory.py} (91%) rename upstream_utils/{update_mpack.py => mpack.py} (80%) rename upstream_utils/{update_protobuf.py => protobuf.py} (97%) rename upstream_utils/{update_sleipnir.py => sleipnir.py} (76%) rename upstream_utils/{update_stack_walker.py => stack_walker.py} (64%) diff --git a/.github/workflows/upstream-utils.yml b/.github/workflows/upstream-utils.yml index 102aaf621bc..e9c04a45823 100644 --- a/.github/workflows/upstream-utils.yml +++ b/.github/workflows/upstream-utils.yml @@ -30,50 +30,61 @@ jobs: run: | git config --global user.email "you@example.com" git config --global user.name "Your Name" - - name: Run update_eigen.py + - name: Run eigen.py run: | cd upstream_utils - ./update_eigen.py - - name: Run update_fmt.py + ./eigen.py clone + ./eigen.py copy-upstream-to-thirdparty + - name: Run fmt.py run: | cd upstream_utils - ./update_fmt.py - - name: Run update_gcem.py + ./fmt.py clone + ./fmt.py copy-upstream-to-thirdparty + - name: Run gcem.py run: | cd upstream_utils - ./update_gcem.py - - name: Run update_json.py + ./gcem.py clone + ./gcem.py copy-upstream-to-thirdparty + - name: Run json.py run: | cd upstream_utils - ./update_json.py - - name: Run update_libuv.py + ./json.py clone + ./json.py copy-upstream-to-thirdparty + - name: Run libuv.py run: | cd upstream_utils - ./update_libuv.py - - name: Run update_llvm.py + ./libuv.py clone + ./libuv.py copy-upstream-to-thirdparty + - name: Run llvm.py run: | cd upstream_utils - ./update_llvm.py - - name: Run update_mpack.py + ./llvm.py clone + ./llvm.py copy-upstream-to-thirdparty + - name: Run mpack.py run: | cd upstream_utils - ./update_mpack.py - - name: Run update_stack_walker.py + ./mpack.py clone + ./mpack.py copy-upstream-to-thirdparty + - name: Run stack_walker.py run: | cd upstream_utils - ./update_stack_walker.py - - name: Run update_memory.py + ./stack_walker.py clone + ./stack_walker.py copy-upstream-to-thirdparty + - name: Run memory.py run: | cd upstream_utils - ./update_memory.py - - name: Run update_protobuf.py + ./memory.py clone + ./memory.py copy-upstream-to-thirdparty + - name: Run protobuf.py run: | cd upstream_utils - ./update_protobuf.py - - name: Run update_sleipnir.py + ./protobuf.py clone + ./protobuf.py copy-upstream-to-thirdparty + - name: Run sleipnir.py run: | cd upstream_utils - ./update_sleipnir.py + ./sleipnir.py clone + ./sleipnir.py copy-upstream-to-thirdparty - name: Add untracked files to index so they count as changes run: git add -A - name: Check output diff --git a/upstream_utils/README.md b/upstream_utils/README.md index 979dd0d6727..2e200ae5b52 100644 --- a/upstream_utils/README.md +++ b/upstream_utils/README.md @@ -20,59 +20,24 @@ versions. Each library has its own patch directory (e.g., `lib_patches`). The example below will update a hypothetical library called `lib` to the tag `2.0`. -Start in the `upstream_utils` folder. Restore the original repo. +Start in the `upstream_utils` folder. Make sure a clone of the upstream repo exists. ```bash -./update_.py +./.py clone ``` -Navigate to the repo. +Rebase the clone of the upstream repo. ```bash -cd /tmp/lib +./.py rebase 2.0 ``` -Fetch the desired version using one of the following methods. +Update the `upstream_utils` patch files and the tag in the script. ```bash -# Fetch a full branch or tag -git fetch origin 2.0 - -# Fetch just a tag (useful for expensive-to-clone repos) -git fetch --depth 1 origin tag 2.0 -``` - -Rebase any patches onto the new version. If the old version and new version are -on the same branch, run the following. -```bash -git rebase 2.0 -``` - -If the old version and new version are on different branches (e.g., -llvm-project), use interactive rebase instead and remove commits that are common -between the two branches from the list of commits to rebase. In other words, -only commits representing downstream patches should be listed. -```bash -git rebase -i 2.0 -``` - -Generate patch files for the new version. -```bash -git format-patch 2.0..HEAD --zero-commit --abbrev=40 --no-signature -``` - -Move the patch files to `upstream_utils`. -``` -mv *.patch allwpilib/upstream_utils/lib_patches -``` - -Navigate back to `upstream_utils`. -```bash -cd allwpilib/upstream_utils +./.py format-patch ``` -Modify the version number in the call to `setup_upstream_repo()` in -`update_.py`, then rerun `update_.py` to reimport the thirdparty -files. +Copy the updated upstream files into the thirdparty files within allwpilib. ```bash -./update_.py +./.py copy-upstream-to-thirdparty ``` ## Adding patch to thirdparty library @@ -80,12 +45,17 @@ files. The example below will add a new patch file to a hypothetical library called `lib` (Replace `` with `llvm`, `fmt`, `eigen`, ... in the following steps). -Start in the `upstream_utils` folder. Restore the original repo. +Start in the `upstream_utils` folder. Make sure a clone of the upstream repo exists. +```bash +./.py clone +``` + +Update the clone of the upstream repo. ```bash -./update_.py +./.py reset ``` -Navigate to the repo. +Navigate to the repo. If you can't find it, the directory of the clone is printed at the start of the `clone` command. ```bash cd /tmp/ ``` @@ -96,24 +66,17 @@ git add ... git commit -m "..." ``` -Generate patch files. +Navigate back to `upstream_utils`. ```bash -git format-patch 2.0..HEAD --zero-commit --abbrev=40 --no-signature -``` -where `2.0` is replaced with the version specified in `update_.py`. - -Move the patch files to `upstream_utils`. -``` -mv *.patch allwpilib/upstream_utils/_patches +cd allwpilib/upstream_utils ``` -Navigate back to `upstream_utils`. +Update the `upstream_utils` patch files. ```bash -cd allwpilib/upstream_utils +./.py format-patch ``` -Update the list of patch files in `update_.py`, then rerun -`update_.py` to reimport the thirdparty files. +Update the list of patch files in `.py`, then rerun `.py` to reimport the thirdparty files. ```bash -./update_.py +./.py copy-upstream-to-thirdparty ``` diff --git a/upstream_utils/update_eigen.py b/upstream_utils/eigen.py similarity index 87% rename from upstream_utils/update_eigen.py rename to upstream_utils/eigen.py index 66c82385e97..ace408ecb0a 100755 --- a/upstream_utils/update_eigen.py +++ b/upstream_utils/eigen.py @@ -5,11 +5,9 @@ import shutil from upstream_utils import ( - get_repo_root, - clone_repo, comment_out_invalid_includes, walk_cwd_and_copy_if, - git_am, + Lib, ) @@ -94,25 +92,9 @@ def unsupported_inclusions(dp, f): return "MatrixFunctions" in abspath -def main(): - upstream_root = clone_repo( - "https://gitlab.com/libeigen/eigen.git", - # master on 2024-05-22 - "c4d84dfddc9f9edef0fdbe7cf9966d2f4a303198", - shallow=False, - ) - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): wpimath = os.path.join(wpilib_root, "wpimath") - # Apply patches to upstream Git repo - os.chdir(upstream_root) - for f in [ - "0001-Disable-warnings.patch", - "0002-Intellisense-fix.patch", - "0003-Suppress-has_denorm-and-has_denorm_loss-deprecation-.patch", - ]: - git_am(os.path.join(wpilib_root, "upstream_utils/eigen_patches", f)) - # Delete old install for d in ["src/main/native/thirdparty/eigen/include"]: shutil.rmtree(os.path.join(wpimath, d), ignore_errors=True) @@ -139,10 +121,24 @@ def main(): ) shutil.copyfile( - os.path.join(upstream_root, ".clang-format"), + ".clang-format", os.path.join(wpimath, "src/main/native/thirdparty/eigen/include/.clang-format"), ) +def main(): + name = "eigen" + url = "https://gitlab.com/libeigen/eigen.git" + tag = "c4d84dfddc9f9edef0fdbe7cf9966d2f4a303198" + patch_list = [ + "0001-Disable-warnings.patch", + "0002-Intellisense-fix.patch", + "0003-Suppress-has_denorm-and-has_denorm_loss-deprecation-.patch", + ] + + eigen = Lib(name, url, tag, patch_list, copy_upstream_src) + eigen.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/update_expected.py b/upstream_utils/expected.py similarity index 69% rename from upstream_utils/update_expected.py rename to upstream_utils/expected.py index 1b459fe5ac3..08569e3561b 100755 --- a/upstream_utils/update_expected.py +++ b/upstream_utils/expected.py @@ -10,26 +10,18 @@ comment_out_invalid_includes, walk_cwd_and_copy_if, git_am, + Lib, ) -def main(): - upstream_root = clone_repo( - "https://github.com/TartanLlama/expected", - # master on 2024-01-25 - "3f0ca7b19253129700a073abfa6d8638d9f7c80c", - shallow=False, - ) - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): wpiutil = os.path.join(wpilib_root, "wpiutil") # Copy expected header into allwpilib dest_filename = os.path.join( wpiutil, "src/main/native/thirdparty/expected/include/wpi/expected" ) - shutil.copyfile( - os.path.join(upstream_root, "include/tl/expected.hpp"), dest_filename - ) + shutil.copyfile("include/tl/expected.hpp", dest_filename) # Rename namespace from tl to wpi with open(dest_filename) as f: @@ -41,5 +33,15 @@ def main(): f.write(content) +def main(): + name = "expected" + url = "https://github.com/TartanLlama/expected" + # master on 2024-01-25 + tag = "3f0ca7b19253129700a073abfa6d8638d9f7c80c" + + expected = Lib(name, url, tag, [], copy_upstream_src) + expected.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/update_fmt.py b/upstream_utils/fmt.py similarity index 80% rename from upstream_utils/update_fmt.py rename to upstream_utils/fmt.py index 94aef193f71..8f03859f54c 100755 --- a/upstream_utils/update_fmt.py +++ b/upstream_utils/fmt.py @@ -9,19 +9,13 @@ comment_out_invalid_includes, walk_cwd_and_copy_if, git_am, + Lib, ) -def main(): - upstream_root = clone_repo("https://github.com/fmtlib/fmt", "11.0.1") - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): wpiutil = os.path.join(wpilib_root, "wpiutil") - # Apply patches to upstream Git repo - os.chdir(upstream_root) - for f in ["0001-Suppress-warnings-we-can-t-fix.patch"]: - git_am(os.path.join(wpilib_root, "upstream_utils/fmt_patches", f)) - # Delete old install for d in [ "src/main/native/thirdparty/fmtlib/src", @@ -51,5 +45,16 @@ def main(): ) +def main(): + name = "fmt" + url = "https://github.com/fmtlib/fmt" + tag = "11.0.1" + + patch_list = ["0001-Suppress-warnings-we-can-t-fix.patch"] + + fmt = Lib(name, url, tag, patch_list, copy_upstream_src) + fmt.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/update_gcem.py b/upstream_utils/gcem.py similarity index 76% rename from upstream_utils/update_gcem.py rename to upstream_utils/gcem.py index 20f62425962..b6fd472a72f 100755 --- a/upstream_utils/update_gcem.py +++ b/upstream_utils/gcem.py @@ -9,22 +9,13 @@ comment_out_invalid_includes, walk_cwd_and_copy_if, git_am, + Lib, ) -def main(): - upstream_root = clone_repo("https://github.com/kthohr/gcem.git", "v1.18.0") - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): wpimath = os.path.join(wpilib_root, "wpimath") - # Apply patches to upstream Git repo - os.chdir(upstream_root) - for f in [ - "0001-Call-std-functions-if-not-constant-evaluated.patch", - "0002-Add-hypot-x-y-z.patch", - ]: - git_am(os.path.join(wpilib_root, "upstream_utils/gcem_patches", f)) - # Delete old install for d in [ "src/main/native/thirdparty/gcem/include", @@ -43,5 +34,19 @@ def main(): ) +def main(): + name = "gcem" + url = "https://github.com/kthohr/gcem.git" + tag = "v1.18.0" + + patch_list = [ + "0001-Call-std-functions-if-not-constant-evaluated.patch", + "0002-Add-hypot-x-y-z.patch", + ] + + gcem = Lib(name, url, tag, patch_list, copy_upstream_src) + gcem.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/update_json.py b/upstream_utils/json.py similarity index 78% rename from upstream_utils/update_json.py rename to upstream_utils/json.py index 9cad98d5fa3..78924ef2a1e 100755 --- a/upstream_utils/update_json.py +++ b/upstream_utils/json.py @@ -8,27 +8,13 @@ clone_repo, walk_if, git_am, + Lib, ) -def main(): - upstream_root = clone_repo("https://github.com/nlohmann/json", "v3.11.3") - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): wpiutil = os.path.join(wpilib_root, "wpiutil") - # Apply patches to upstream Git repo - os.chdir(upstream_root) - for f in [ - "0001-Remove-version-from-namespace.patch", - "0002-Make-serializer-public.patch", - "0003-Make-dump_escaped-take-std-string_view.patch", - "0004-Add-llvm-stream-support.patch", - ]: - git_am( - os.path.join(wpilib_root, "upstream_utils/json_patches", f), - use_threeway=True, - ) - # Delete old install for d in [ "src/main/native/thirdparty/json/include", @@ -36,11 +22,9 @@ def main(): shutil.rmtree(os.path.join(wpiutil, d), ignore_errors=True) # Create lists of source and destination files - os.chdir(os.path.join(upstream_root, "include/nlohmann")) + os.chdir("include/nlohmann") files = walk_if(".", lambda dp, f: True) - src_include_files = [ - os.path.join(os.path.join(upstream_root, "include/nlohmann"), f) for f in files - ] + src_include_files = [os.path.abspath(f) for f in files] wpiutil_json_root = os.path.join( wpiutil, "src/main/native/thirdparty/json/include/wpi" ) @@ -74,5 +58,24 @@ def main(): f.write(content) +def main(): + name = "json" + url = "https://github.com/nlohmann/json" + tag = "v3.11.3" + + patch_list = [ + "0001-Remove-version-from-namespace.patch", + "0002-Make-serializer-public.patch", + "0003-Make-dump_escaped-take-std-string_view.patch", + "0004-Add-llvm-stream-support.patch", + ] + patch_options = { + "use_threeway": True, + } + + json = Lib(name, url, tag, patch_list, copy_upstream_src, patch_options) + json.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/update_libuv.py b/upstream_utils/libuv.py similarity index 86% rename from upstream_utils/update_libuv.py rename to upstream_utils/libuv.py index 0290c4d73a8..9a2865838cf 100755 --- a/upstream_utils/update_libuv.py +++ b/upstream_utils/libuv.py @@ -9,30 +9,13 @@ comment_out_invalid_includes, walk_cwd_and_copy_if, git_am, + Lib, ) -def main(): - upstream_root = clone_repo("https://github.com/libuv/libuv", "v1.48.0") - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): wpinet = os.path.join(wpilib_root, "wpinet") - # Apply patches to upstream Git repo - os.chdir(upstream_root) - for f in [ - "0001-Revert-win-process-write-minidumps-when-sending-SIGQ.patch", - "0002-Fix-missing-casts.patch", - "0003-Fix-warnings.patch", - "0004-Preprocessor-cleanup.patch", - "0005-Cleanup-problematic-language.patch", - "0006-Fix-Win32-warning-suppression-pragma.patch", - "0007-Use-C-atomics.patch", - "0008-Remove-static-from-array-indices.patch", - "0009-Add-pragmas-for-missing-libraries-and-set-_WIN32_WIN.patch", - "0010-Remove-swearing.patch", - ]: - git_am(os.path.join(wpilib_root, "upstream_utils/libuv_patches", f)) - # Delete old install for d in ["src/main/native/thirdparty/libuv"]: shutil.rmtree(os.path.join(wpinet, d), ignore_errors=True) @@ -71,5 +54,27 @@ def main(): ) +def main(): + name = "libuv" + url = "https://github.com/libuv/libuv" + tag = "v1.48.0" + + patch_list = [ + "0001-Revert-win-process-write-minidumps-when-sending-SIGQ.patch", + "0002-Fix-missing-casts.patch", + "0003-Fix-warnings.patch", + "0004-Preprocessor-cleanup.patch", + "0005-Cleanup-problematic-language.patch", + "0006-Fix-Win32-warning-suppression-pragma.patch", + "0007-Use-C-atomics.patch", + "0008-Remove-static-from-array-indices.patch", + "0009-Add-pragmas-for-missing-libraries-and-set-_WIN32_WIN.patch", + "0010-Remove-swearing.patch", + ] + + libuv = Lib(name, url, tag, patch_list, copy_upstream_src) + libuv.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/update_llvm.py b/upstream_utils/llvm.py similarity index 96% rename from upstream_utils/update_llvm.py rename to upstream_utils/llvm.py index d2d3c379df6..abbc077a655 100755 --- a/upstream_utils/update_llvm.py +++ b/upstream_utils/llvm.py @@ -9,6 +9,7 @@ comment_out_invalid_includes, walk_cwd_and_copy_if, git_am, + Lib, ) @@ -170,14 +171,20 @@ def overwrite_tests(wpiutil_root, llvm_root): run_global_replacements(wpi_files) -def main(): - upstream_root = clone_repo("https://github.com/llvm/llvm-project", "llvmorg-18.1.8") - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): + upstream_root = os.path.abspath(".") wpiutil = os.path.join(wpilib_root, "wpiutil") - # Apply patches to upstream Git repo - os.chdir(upstream_root) - for f in [ + overwrite_source(wpiutil, upstream_root) + overwrite_tests(wpiutil, upstream_root) + + +def main(): + name = "llvm" + url = "https://github.com/llvm/llvm-project" + tag = "llvmorg-18.1.8" + + patch_list = [ "0001-Remove-StringRef-ArrayRef-and-Optional.patch", "0002-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch", "0003-Change-unique_function-storage-size.patch", @@ -215,14 +222,13 @@ def main(): "0035-Remove-auto-conversion-from-raw_ostream.patch", "0036-Add-SmallVector-erase_if.patch", "0037-Fix-AlignedCharArrayUnion-for-C-23.patch", - ]: - git_am( - os.path.join(wpilib_root, "upstream_utils/llvm_patches", f), - use_threeway=True, - ) + ] + patch_options = { + "use_threeway": True, + } - overwrite_source(wpiutil, upstream_root) - overwrite_tests(wpiutil, upstream_root) + llvm = Lib(name, url, tag, patch_list, copy_upstream_src, patch_options) + llvm.main() if __name__ == "__main__": diff --git a/upstream_utils/update_memory.py b/upstream_utils/memory.py similarity index 91% rename from upstream_utils/update_memory.py rename to upstream_utils/memory.py index 6645aaf60cf..4a618584220 100755 --- a/upstream_utils/update_memory.py +++ b/upstream_utils/memory.py @@ -9,6 +9,7 @@ comment_out_invalid_includes, walk_if, copy_to, + Lib, ) @@ -58,9 +59,7 @@ def run_global_replacements(memory_files): f.write(content) -def main(): - upstream_root = clone_repo("https://github.com/foonathan/memory", "v0.7-3") - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): wpiutil = os.path.join(wpilib_root, "wpiutil") # Delete old install @@ -71,7 +70,6 @@ def main(): shutil.rmtree(os.path.join(wpiutil, d), ignore_errors=True) # Copy sources - os.chdir(upstream_root) src_files = walk_if("src", lambda dp, f: f.endswith(".cpp") or f.endswith(".hpp")) src_files = copy_to( src_files, os.path.join(wpiutil, "src/main/native/thirdparty/memory") @@ -80,7 +78,7 @@ def main(): run_source_replacements(src_files) # Copy headers - os.chdir(os.path.join(upstream_root, "include", "foonathan")) + os.chdir(os.path.join("include", "foonathan")) include_files = walk_if(".", lambda dp, f: f.endswith(".hpp")) include_files = copy_to( include_files, @@ -100,5 +98,14 @@ def main(): ) +def main(): + name = "memory" + url = "https://github.com/foonathan/memory" + tag = "v0.7-3" + + memory = Lib(name, url, tag, [], copy_upstream_src) + memory.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/update_mpack.py b/upstream_utils/mpack.py similarity index 80% rename from upstream_utils/update_mpack.py rename to upstream_utils/mpack.py index 68315e933a9..ad395377a64 100755 --- a/upstream_utils/update_mpack.py +++ b/upstream_utils/mpack.py @@ -9,12 +9,11 @@ clone_repo, walk_cwd_and_copy_if, git_am, + Lib, ) -def main(): - upstream_root = clone_repo("https://github.com/ludocode/mpack", "v1.1.1") - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): wpiutil = os.path.join(wpilib_root, "wpiutil") # Delete old install @@ -24,19 +23,6 @@ def main(): ]: shutil.rmtree(os.path.join(wpiutil, d), ignore_errors=True) - # Apply patches to upstream Git repo - os.chdir(upstream_root) - - for f in [ - "0001-Don-t-emit-inline-defs.patch", - "0002-Update-amalgamation-script.patch", - "0003-Use-namespace-for-C.patch", - "0004-Group-doxygen-into-MPack-module.patch", - ]: - git_am( - os.path.join(wpilib_root, "upstream_utils/mpack_patches", f), - ) - # Run the amalgmation script subprocess.check_call(["bash", "tools/amalgamate.sh"]) @@ -56,5 +42,21 @@ def main(): ) +def main(): + name = "mpack" + url = "https://github.com/ludocode/mpack" + tag = "v1.1.1" + + patch_list = [ + "0001-Don-t-emit-inline-defs.patch", + "0002-Update-amalgamation-script.patch", + "0003-Use-namespace-for-C.patch", + "0004-Group-doxygen-into-MPack-module.patch", + ] + + mpack = Lib(name, url, tag, patch_list, copy_upstream_src) + mpack.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/update_protobuf.py b/upstream_utils/protobuf.py similarity index 97% rename from upstream_utils/update_protobuf.py rename to upstream_utils/protobuf.py index 1f004cd0c42..8b2adf5347b 100755 --- a/upstream_utils/update_protobuf.py +++ b/upstream_utils/protobuf.py @@ -11,6 +11,7 @@ walk_cwd_and_copy_if, walk_if, git_am, + Lib, ) protobuf_lite_sources = set( @@ -255,31 +256,10 @@ def matches(dp, f, files): return p in files -def main(): - upstream_root = clone_repo( - "https://github.com/protocolbuffers/protobuf", "v3.21.12" - ) - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): + upstream_root = os.path.abspath(".") wpiutil = os.path.join(wpilib_root, "wpiutil") - # Apply patches to upstream Git repo - os.chdir(upstream_root) - for f in [ - "0001-Fix-sign-compare-warnings.patch", - "0002-Remove-redundant-move.patch", - "0003-Fix-maybe-uninitialized-warnings.patch", - "0004-Fix-coded_stream-WriteRaw.patch", - "0005-Suppress-enum-enum-conversion-warning.patch", - "0006-Fix-noreturn-function-returning.patch", - "0007-Work-around-GCC-12-restrict-warning-compiler-bug.patch", - "0008-Disable-MSVC-switch-warning.patch", - "0009-Disable-unused-function-warning.patch", - "0010-Disable-pedantic-warning.patch", - "0011-Avoid-use-of-sprintf.patch", - "0012-Suppress-stringop-overflow-warning-false-positives.patch", - ]: - git_am(os.path.join(wpilib_root, "upstream_utils/protobuf_patches", f)) - # Delete old install for d in [ "src/main/native/thirdparty/protobuf/src", @@ -304,5 +284,29 @@ def main(): ) +def main(): + name = "protobuf" + url = "https://github.com/protocolbuffers/protobuf" + tag = "v3.21.12" + + patch_list = [ + "0001-Fix-sign-compare-warnings.patch", + "0002-Remove-redundant-move.patch", + "0003-Fix-maybe-uninitialized-warnings.patch", + "0004-Fix-coded_stream-WriteRaw.patch", + "0005-Suppress-enum-enum-conversion-warning.patch", + "0006-Fix-noreturn-function-returning.patch", + "0007-Work-around-GCC-12-restrict-warning-compiler-bug.patch", + "0008-Disable-MSVC-switch-warning.patch", + "0009-Disable-unused-function-warning.patch", + "0010-Disable-pedantic-warning.patch", + "0011-Avoid-use-of-sprintf.patch", + "0012-Suppress-stringop-overflow-warning-false-positives.patch", + ] + + protobuf = Lib(name, url, tag, patch_list, copy_upstream_src) + protobuf.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/update_sleipnir.py b/upstream_utils/sleipnir.py similarity index 76% rename from upstream_utils/update_sleipnir.py rename to upstream_utils/sleipnir.py index 4b783c82bab..11b20cc29a8 100755 --- a/upstream_utils/update_sleipnir.py +++ b/upstream_utils/sleipnir.py @@ -9,30 +9,13 @@ copy_to, walk_cwd_and_copy_if, git_am, + Lib, ) -def main(): - upstream_root = clone_repo( - "https://github.com/SleipnirGroup/Sleipnir", - # main on 2024-07-09 - "b6ffa2d4fdb99cab1bf79491f715a6a9a86633b5", - shallow=False, - ) - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): wpimath = os.path.join(wpilib_root, "wpimath") - # Apply patches to upstream Git repo - os.chdir(upstream_root) - for f in [ - "0001-Remove-using-enum-declarations.patch", - "0002-Use-fmtlib.patch", - "0003-Remove-unsupported-constexpr.patch", - "0004-Use-wpi-SmallVector.patch", - "0005-Suppress-clang-tidy-false-positives.patch", - ]: - git_am(os.path.join(wpilib_root, "upstream_utils/sleipnir_patches", f)) - # Delete old install for d in [ "src/main/native/thirdparty/sleipnir/src", @@ -41,7 +24,6 @@ def main(): shutil.rmtree(os.path.join(wpimath, d), ignore_errors=True) # Copy Sleipnir source files into allwpilib - os.chdir(upstream_root) src_files = [os.path.join(dp, f) for dp, dn, fn in os.walk("src") for f in fn] src_files = copy_to( src_files, os.path.join(wpimath, "src/main/native/thirdparty/sleipnir") @@ -65,10 +47,28 @@ def main(): ".styleguide-license", ]: shutil.copyfile( - os.path.join(upstream_root, filename), + filename, os.path.join(wpimath, "src/main/native/thirdparty/sleipnir", filename), ) +def main(): + name = "sleipnir" + url = "https://github.com/SleipnirGroup/Sleipnir" + # main on 2024-07-09 + tag = "b6ffa2d4fdb99cab1bf79491f715a6a9a86633b5" + + patch_list = [ + "0001-Remove-using-enum-declarations.patch", + "0002-Use-fmtlib.patch", + "0003-Remove-unsupported-constexpr.patch", + "0004-Use-wpi-SmallVector.patch", + "0005-Suppress-clang-tidy-false-positives.patch", + ] + + sleipnir = Lib(name, url, tag, patch_list, copy_upstream_src) + sleipnir.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/update_stack_walker.py b/upstream_utils/stack_walker.py similarity index 64% rename from upstream_utils/update_stack_walker.py rename to upstream_utils/stack_walker.py index a58886ec799..190f12d04d9 100755 --- a/upstream_utils/update_stack_walker.py +++ b/upstream_utils/stack_walker.py @@ -10,11 +10,12 @@ comment_out_invalid_includes, walk_cwd_and_copy_if, git_am, + Lib, ) -def crlf_to_lf(stackwalker_dir): - for root, _, files in os.walk(stackwalker_dir): +def crlf_to_lf(): + for root, _, files in os.walk("."): if ".git" in root: continue @@ -28,35 +29,13 @@ def crlf_to_lf(stackwalker_dir): with open(filename, "wb") as f: f.write(content) - cwd = os.getcwd() - os.chdir(stackwalker_dir) subprocess.check_call(["git", "add", "-A"]) subprocess.check_call(["git", "commit", "-m", "Fix line endings"]) - os.chdir(cwd) -def main(): - upstream_root = clone_repo( - "https://github.com/JochenKalmbach/StackWalker", - "5b0df7a4db8896f6b6dc45d36e383c52577e3c6b", - shallow=False, - ) - wpilib_root = get_repo_root() +def copy_upstream_src(wpilib_root): wpiutil = os.path.join(wpilib_root, "wpiutil") - # Run CRLF -> LF before trying any patches - crlf_to_lf(upstream_root) - - # Apply patches to upstream Git repo - os.chdir(upstream_root) - for f in [ - "0001-Add-advapi-pragma.patch", - ]: - git_am( - os.path.join(wpilib_root, "upstream_utils/stack_walker_patches", f), - ignore_whitespace=True, - ) - shutil.copy( os.path.join("Main", "StackWalker", "StackWalker.h"), os.path.join(wpiutil, "src/main/native/windows/StackWalker.h"), @@ -68,5 +47,30 @@ def main(): ) +def main(): + name = "stack_walker" + url = "https://github.com/JochenKalmbach/StackWalker" + tag = "5b0df7a4db8896f6b6dc45d36e383c52577e3c6b" + + patch_list = [ + "0001-Add-advapi-pragma.patch", + ] + patch_options = { + "ignore_whitespace": True, + } + + stack_walker = Lib( + name, + url, + tag, + patch_list, + copy_upstream_src, + patch_options, + pre_patch_hook=crlf_to_lf, + pre_patch_commits=1, + ) + stack_walker.main() + + if __name__ == "__main__": main() diff --git a/upstream_utils/upstream_utils.py b/upstream_utils/upstream_utils.py index ccf668b738f..5851df11f95 100644 --- a/upstream_utils/upstream_utils.py +++ b/upstream_utils/upstream_utils.py @@ -1,7 +1,9 @@ +import argparse import os import re import shutil import subprocess +import sys import tempfile @@ -198,3 +200,411 @@ def git_am(patch, use_threeway=False, ignore_whitespace=False): args.append("--ignore-whitespace") subprocess.check_output(args + [patch]) + + +def has_git_rev(rev): + """Checks whether the Git repository in the current directory has the given + revision. + + Keyword arguments: + rev -- The revision to check + + Returns: + True if the revision exists, otherwise False. + """ + cmd = ["git", "rev-parse", "--verify", "-q", rev] + return subprocess.run(cmd, stdout=subprocess.DEVNULL).returncode == 0 + + +class Lib: + def __init__( + self, + name, + url, + tag, + patch_list, + copy_upstream_src, + patch_options={}, + *, + pre_patch_hook=None, + pre_patch_commits=0, + ): + """Initializes a Lib instance. + + Keyword arguments: + name -- The name of the library. + url -- The URL of the upstream repository. + tag -- The tag in the upstream repository to use. Can be any + (e.g., commit hash or tag). + patch_list -- The list of patches in the patch directory to apply. + copy_upstream_src -- A callable that takes the path to the wpilib root + and copies the files from the clone of the upstream + into the appropriate thirdparty directory. Will + only be called when the current directory is the + upstream clone. + patch_options -- The dictionary of options to use when applying patches. + Corresponds to the parameters of git_am. + + Keyword-only arguments: + pre_patch_hook -- Optional callable taking no parameters that will be + called before applying patches. + pre_patch_commits -- Number of commits added by pre_patch_hook. + """ + self.name = name + self.url = url + self.old_tag = tag + self.patch_list = patch_list + self.copy_upstream_src = copy_upstream_src + self.patch_options = patch_options + self.pre_patch_hook = pre_patch_hook + self.pre_patch_commits = pre_patch_commits + self.wpilib_root = get_repo_root() + + def check_patches(self): + """Checks that the patch list supplied to the constructor matches the + patches in the patch directory. + """ + patch_directory_patches = set() + patch_directory = os.path.join( + self.wpilib_root, f"upstream_utils/{self.name}_patches" + ) + if os.path.exists(patch_directory): + for f in os.listdir(patch_directory): + if f.endswith(".patch"): + patch_directory_patches.add(f) + patches = set(self.patch_list) + patch_directory_only = sorted(patch_directory_patches - patches) + patch_list_only = sorted(patches - patch_directory_patches) + common_patches = sorted(patch_directory_patches & patches) + warning = False + if patch_directory_only: + print( + f"WARNING: The patch directory has patches {patch_directory_only} not in the patch list" + ) + warning = True + if patch_list_only: + print( + f"WARNING: The patch list has patches {patch_list_only} not in the patch directory" + ) + warning = True + if warning and common_patches: + print( + f" Note: The patch directory and the patch list both have patches {common_patches}" + ) + + def get_repo_path(self, tempdir=None): + """Returns the path to the clone of the upstream repository. + + Keyword argument: + tempdir -- The path to the temporary directory to use. If None (the + default), uses tempfile.gettempdir(). + + Returns: + The path to the clone of the upstream repository. Will be absolute if + tempdir is absolute. + """ + if tempdir is None: + tempdir = tempfile.gettempdir() + repo = os.path.basename(self.url) + dest = os.path.join(tempdir, repo) + dest = dest.removesuffix(".git") + return dest + + def open_repo(self, *, err_msg_if_absent): + """Changes the current working directory to the upstream repository. If + err_msg_if_absent is not None and the upstream repository does not + exist, the program exits with return code 1. + + Keyword-only argument: + err_msg_if_absent -- The error message to print to stderr if the + upstream repository does not exist. If None, the upstream repository + will be cloned without emitting any warnings. + """ + os.chdir(tempfile.gettempdir()) + + dest = self.get_repo_path(os.getcwd()) + + print(f"INFO: Opening repository at {dest}") + + if not os.path.exists(dest): + if err_msg_if_absent is None: + subprocess.run(["git", "clone", "--filter=tree:0", self.url]) + else: + print(err_msg_if_absent, file=sys.stderr) + exit(1) + os.chdir(dest) + + def get_root_tags(self): + """Returns a list of potential root tags. + + Returns: + A list of the potential root tags. + """ + root_tag_output = subprocess.run( + ["git", "tag", "--list", "upstream_utils_root-*"], + capture_output=True, + text=True, + ).stdout + return root_tag_output.splitlines() + + def get_root_tag(self): + """Returns the root tag (the default tag to apply the patches relative + to). If there are multiple candidates, prints an error to stderr and the + program exits with return code 1. + + Returns: + The root tag. + """ + root_tags = self.get_root_tags() + if len(root_tags) == 0: + print( + "ERROR: Could not determine root tag: No tags match 'upstream_utils_root-*'", + file=sys.stderr, + ) + exit(1) + if len(root_tags) > 1: + print( + f"ERROR: Could not determine root tag: Multiple candidates: {root_tags}", + file=sys.stderr, + ) + exit(1) + return root_tags[0] + + def set_root_tag(self, tag): + """Sets the root tag, deleting any potential candidates first. + + Keyword argument: + tag -- The tag to set as the root tag. + """ + root_tags = self.get_root_tags() + + if len(root_tags) > 1: + print(f"WARNING: Deleting multiple root tags {root_tags}", file=sys.stderr) + + for root_tag in root_tags: + subprocess.run(["git", "tag", "-d", root_tag]) + + subprocess.run(["git", "tag", f"upstream_utils_root-{tag}", tag]) + + def apply_patches(self): + """Applies the patches listed in the patch list to the current + directory. + """ + if self.pre_patch_hook is not None: + self.pre_patch_hook() + + for f in self.patch_list: + git_am( + os.path.join( + self.wpilib_root, f"upstream_utils/{self.name}_patches", f + ), + **self.patch_options, + ) + + def replace_tag(self, tag): + """Replaces the tag in the script. + + Keyword argument: + tag -- The tag to replace the script tag with. + """ + path = os.path.join(self.wpilib_root, f"upstream_utils/{self.name}.py") + with open(path, "r") as file: + lines = file.readlines() + + previous_text = f'tag = "{self.old_tag}"' + new_text = f'tag = "{tag}"' + for i in range(len(lines)): + if previous_text in lines[i]: + if i - 1 >= 0 and "#" in lines[i - 1]: + print( + f"WARNING: Automatically updating tag in line {i + 1} with a comment above it that may need updating.", + file=sys.stderr, + ) + lines[i] = lines[i].replace(previous_text, new_text) + + with open(path, "w") as file: + file.writelines(lines) + + def info(self): + """Prints info about the library to stdout.""" + print(f"Repository name: {self.name}") + print(f"Upstream URL: {self.url}") + print(f"Upstream tag: {self.old_tag}") + print(f"Path to upstream clone: {self.get_repo_path()}") + print(f"Patches to apply: {self.patch_list}") + print(f"Patch options: {self.patch_options}") + print(f"Pre patch commits: {self.pre_patch_commits}") + print(f"WPILib root: {self.wpilib_root}") + + def clone(self): + """Clones the upstream repository and sets it up.""" + self.open_repo(err_msg_if_absent=None) + + subprocess.run(["git", "switch", "--detach", self.old_tag]) + + self.set_root_tag(self.old_tag) + + def reset(self): + """Resets the clone of the upstream repository to the state specified by + the script and patches. + """ + self.open_repo( + err_msg_if_absent='There\'s nothing to reset. Run the "clone" command first.' + ) + + subprocess.run(["git", "switch", "--detach", self.old_tag]) + + self.apply_patches() + + self.set_root_tag(self.old_tag) + + def rebase(self, new_tag): + """Rebases the patches. + + Keyword argument: + new_tag -- The tag to rebase onto. + """ + self.open_repo( + err_msg_if_absent='There\'s nothing to rebase. Run the "clone" command first.' + ) + + subprocess.run(["git", "fetch", "origin", new_tag]) + + subprocess.run(["git", "switch", "--detach", self.old_tag]) + + self.apply_patches() + + self.set_root_tag(new_tag) + + subprocess.run(["git", "rebase", "--onto", new_tag, self.old_tag]) + + # Detect merge conflict by detecting if we stopped in the middle of a rebase + if has_git_rev("REBASE_HEAD"): + print( + f"Merge conflicts when rebasing onto {new_tag}! You must manually resolve them.", + file=sys.stderr, + ) + + def format_patch(self): + """Generates patch files for the upstream repository and moves them into + the patch directory. + """ + self.open_repo( + err_msg_if_absent='There\'s nothing to run format-patch on. Run the "clone" and "rebase" commands first.' + ) + + root_tag = self.get_root_tag() + script_tag = root_tag.removeprefix("upstream_utils_root-") + + start_commit = root_tag + if self.pre_patch_commits > 0: + commits_since_tag_output = subprocess.run( + ["git", "log", "--format=format:%h", f"{start_commit}..HEAD"], + capture_output=True, + ).stdout + commits_since_tag = commits_since_tag_output.count(b"\n") + 1 + start_commit = f"HEAD~{commits_since_tag - self.pre_patch_commits}" + + subprocess.run( + [ + "git", + "format-patch", + f"{start_commit}..HEAD", + "--abbrev=40", + "--zero-commit", + "--no-signature", + ] + ) + + patch_dest = os.path.join( + self.wpilib_root, f"upstream_utils/{self.name}_patches" + ) + + if not os.path.exists(patch_dest): + print( + f"WARNING: Patch directory {patch_dest} does not exist", file=sys.stderr + ) + else: + shutil.rmtree(patch_dest) + + is_first = True + for f in os.listdir(): + if f.endswith(".patch"): + if is_first: + os.mkdir(patch_dest) + is_first = False + shutil.move(f, patch_dest) + + self.replace_tag(script_tag) + + def copy_upstream_to_thirdparty(self): + """Copies files from the upstream repository into the thirdparty + directory. + """ + self.open_repo( + err_msg_if_absent='There\'s no repository to copy from. Run the "clone" command first.' + ) + + subprocess.run(["git", "switch", "--detach", self.old_tag]) + + self.apply_patches() + + self.copy_upstream_src(self.wpilib_root) + + def main(self, argv=sys.argv[1:]): + """Processes the given arguments. + + Keyword argument: + argv -- The arguments to process. Defaults to the arguments passed to + the program. + """ + parser = argparse.ArgumentParser( + description=f"CLI manager of the {self.name} upstream library" + ) + subparsers = parser.add_subparsers(dest="subcommand", required=True) + + subparsers.add_parser( + "info", help="Displays information about the upstream library" + ) + + subparsers.add_parser( + "clone", help="Clones the upstream repository in a local tempdir" + ) + + subparsers.add_parser( + "reset", + help="Resets the clone of the upstream repository to the tag and applies patches", + ) + + parser_rebase = subparsers.add_parser( + "rebase", help="Rebases the clone of the upstream repository" + ) + parser_rebase.add_argument("new_tag", help="The tag to rebase onto") + + parser_format_patch = subparsers.add_parser( + "format-patch", + help="Generates patch files for the upstream repository and moves them into the upstream_utils patch directory", + ) + + subparsers.add_parser( + "copy-upstream-to-thirdparty", + help="Copies files from the upstream repository into the thirdparty directory in allwpilib", + ) + + args = parser.parse_args(argv) + + self.wpilib_root = get_repo_root() + if args.subcommand == "info": + self.info() + elif args.subcommand == "clone": + self.clone() + elif args.subcommand == "reset": + self.reset() + elif args.subcommand == "rebase": + self.rebase(args.new_tag) + elif args.subcommand == "format-patch": + self.format_patch() + elif args.subcommand == "copy-upstream-to-thirdparty": + self.copy_upstream_to_thirdparty() + + self.check_patches() From 30c7632ab8c7d69f6344440cc4dc381b1632bcc0 Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Tue, 16 Jul 2024 20:23:11 -0400 Subject: [PATCH 05/10] [wpimath] Make SimpleMotorFeedforward only support discrete feedforward (#6647) Co-authored-by: Tyler Veness --- .../command/MecanumControllerCommand.java | 80 +++++---- .../wpilibj2/command/RamseteCommand.java | 25 ++- .../frc2/command/MecanumControllerCommand.cpp | 19 +-- .../cpp/frc2/command/RamseteCommand.cpp | 11 +- .../ElevatorExponentialProfile/cpp/Robot.cpp | 3 +- .../main/cpp/examples/EventLoop/cpp/Robot.cpp | 7 +- .../FlywheelBangBangController/cpp/Robot.cpp | 1 + .../cpp/subsystems/ShooterSubsystem.cpp | 1 + .../differentialdrivebot/Drivetrain.java | 9 +- .../Drivetrain.java | 9 +- .../subsystems/DriveSubsystem.java | 7 +- .../elevatorexponentialprofile/Robot.java | 5 +- .../elevatortrapezoidprofile/Robot.java | 5 +- .../wpilibj/examples/eventloop/Robot.java | 13 +- .../flywheelbangbangcontroller/Robot.java | 6 +- .../subsystems/ShooterSubsystem.java | 9 +- .../examples/mecanumbot/Drivetrain.java | 15 +- .../mecanumdriveposeestimator/Drivetrain.java | 15 +- .../subsystems/Shooter.java | 16 +- .../Drivetrain.java | 9 +- .../examples/swervebot/SwerveModule.java | 12 +- .../SwerveModule.java | 11 +- .../examples/sysid/subsystems/Shooter.java | 4 +- .../controller/SimpleMotorFeedforward.java | 153 ++++++++++++++---- .../frc/controller/SimpleMotorFeedforward.h | 150 +++++++++++++---- .../SimpleMotorFeedforwardTest.java | 15 +- ...ifferentialDriveVoltageConstraintTest.java | 36 +++-- .../trajectory/ExponentialProfileTest.java | 11 +- .../controller/SimpleMotorFeedforwardTest.cpp | 33 ++-- .../DifferentialDriveVoltageTest.cpp | 12 +- .../cpp/trajectory/ExponentialProfileTest.cpp | 52 +++--- 31 files changed, 538 insertions(+), 216 deletions(-) diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java index 06663c9a800..fa299a51180 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java @@ -4,6 +4,8 @@ package edu.wpi.first.wpilibj2.command; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.Volts; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.math.controller.HolonomicDriveController; @@ -17,6 +19,9 @@ import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages; import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds; import edu.wpi.first.math.trajectory.Trajectory; +import edu.wpi.first.units.Distance; +import edu.wpi.first.units.MutableMeasure; +import edu.wpi.first.units.Velocity; import edu.wpi.first.wpilibj.Timer; import java.util.function.Consumer; import java.util.function.Supplier; @@ -55,8 +60,22 @@ public class MecanumControllerCommand extends Command { private final Supplier m_currentWheelSpeeds; private final Consumer m_outputDriveVoltages; private final Consumer m_outputWheelSpeeds; - private MecanumDriveWheelSpeeds m_prevSpeeds; - private double m_prevTime; + private final MutableMeasure> m_prevFrontLeftSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); + private final MutableMeasure> m_prevRearLeftSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); + private final MutableMeasure> m_prevFrontRightSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); + private final MutableMeasure> m_prevRearRightSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); + private final MutableMeasure> m_frontLeftSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); + private final MutableMeasure> m_rearLeftSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); + private final MutableMeasure> m_frontRightSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); + private final MutableMeasure> m_rearRightSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); /** * Constructs a new MecanumControllerCommand that when executed will follow the provided @@ -331,16 +350,20 @@ public void initialize() { var initialYVelocity = initialState.velocityMetersPerSecond * initialState.poseMeters.getRotation().getSin(); - m_prevSpeeds = + MecanumDriveWheelSpeeds prevSpeeds = m_kinematics.toWheelSpeeds(new ChassisSpeeds(initialXVelocity, initialYVelocity, 0.0)); + m_prevFrontLeftSpeedSetpoint.mut_setMagnitude(prevSpeeds.frontLeftMetersPerSecond); + m_prevRearLeftSpeedSetpoint.mut_setMagnitude(prevSpeeds.rearLeftMetersPerSecond); + m_prevFrontRightSpeedSetpoint.mut_setMagnitude(prevSpeeds.frontRightMetersPerSecond); + m_prevRearRightSpeedSetpoint.mut_setMagnitude(prevSpeeds.rearRightMetersPerSecond); + m_timer.restart(); } @Override public void execute() { double curTime = m_timer.get(); - double dt = curTime - m_prevTime; var desiredState = m_trajectory.sample(curTime); @@ -350,10 +373,10 @@ public void execute() { targetWheelSpeeds.desaturate(m_maxWheelVelocityMetersPerSecond); - var frontLeftSpeedSetpoint = targetWheelSpeeds.frontLeftMetersPerSecond; - var rearLeftSpeedSetpoint = targetWheelSpeeds.rearLeftMetersPerSecond; - var frontRightSpeedSetpoint = targetWheelSpeeds.frontRightMetersPerSecond; - var rearRightSpeedSetpoint = targetWheelSpeeds.rearRightMetersPerSecond; + m_frontLeftSpeedSetpoint.mut_setMagnitude(targetWheelSpeeds.frontLeftMetersPerSecond); + m_rearLeftSpeedSetpoint.mut_setMagnitude(targetWheelSpeeds.rearLeftMetersPerSecond); + m_frontRightSpeedSetpoint.mut_setMagnitude(targetWheelSpeeds.frontRightMetersPerSecond); + m_rearRightSpeedSetpoint.mut_setMagnitude(targetWheelSpeeds.rearRightMetersPerSecond); double frontLeftOutput; double rearLeftOutput; @@ -362,44 +385,42 @@ public void execute() { if (m_usePID) { final double frontLeftFeedforward = - m_feedforward.calculate( - frontLeftSpeedSetpoint, - (frontLeftSpeedSetpoint - m_prevSpeeds.frontLeftMetersPerSecond) / dt); + m_feedforward.calculate(m_prevFrontLeftSpeedSetpoint, m_frontLeftSpeedSetpoint).in(Volts); final double rearLeftFeedforward = - m_feedforward.calculate( - rearLeftSpeedSetpoint, - (rearLeftSpeedSetpoint - m_prevSpeeds.rearLeftMetersPerSecond) / dt); + m_feedforward.calculate(m_prevRearLeftSpeedSetpoint, m_rearLeftSpeedSetpoint).in(Volts); final double frontRightFeedforward = - m_feedforward.calculate( - frontRightSpeedSetpoint, - (frontRightSpeedSetpoint - m_prevSpeeds.frontRightMetersPerSecond) / dt); + m_feedforward + .calculate(m_prevFrontRightSpeedSetpoint, m_frontRightSpeedSetpoint) + .in(Volts); final double rearRightFeedforward = - m_feedforward.calculate( - rearRightSpeedSetpoint, - (rearRightSpeedSetpoint - m_prevSpeeds.rearRightMetersPerSecond) / dt); + m_feedforward.calculate(m_prevRearRightSpeedSetpoint, m_rearRightSpeedSetpoint).in(Volts); frontLeftOutput = frontLeftFeedforward + m_frontLeftController.calculate( - m_currentWheelSpeeds.get().frontLeftMetersPerSecond, frontLeftSpeedSetpoint); + m_currentWheelSpeeds.get().frontLeftMetersPerSecond, + m_frontLeftSpeedSetpoint.in(MetersPerSecond)); rearLeftOutput = rearLeftFeedforward + m_rearLeftController.calculate( - m_currentWheelSpeeds.get().rearLeftMetersPerSecond, rearLeftSpeedSetpoint); + m_currentWheelSpeeds.get().rearLeftMetersPerSecond, + m_rearLeftSpeedSetpoint.in(MetersPerSecond)); frontRightOutput = frontRightFeedforward + m_frontRightController.calculate( - m_currentWheelSpeeds.get().frontRightMetersPerSecond, frontRightSpeedSetpoint); + m_currentWheelSpeeds.get().frontRightMetersPerSecond, + m_frontRightSpeedSetpoint.in(MetersPerSecond)); rearRightOutput = rearRightFeedforward + m_rearRightController.calculate( - m_currentWheelSpeeds.get().rearRightMetersPerSecond, rearRightSpeedSetpoint); + m_currentWheelSpeeds.get().rearRightMetersPerSecond, + m_rearRightSpeedSetpoint.in(MetersPerSecond)); m_outputDriveVoltages.accept( new MecanumDriveMotorVoltages( @@ -408,14 +429,11 @@ public void execute() { } else { m_outputWheelSpeeds.accept( new MecanumDriveWheelSpeeds( - frontLeftSpeedSetpoint, - frontRightSpeedSetpoint, - rearLeftSpeedSetpoint, - rearRightSpeedSetpoint)); + m_frontLeftSpeedSetpoint.in(MetersPerSecond), + m_frontRightSpeedSetpoint.in(MetersPerSecond), + m_rearLeftSpeedSetpoint.in(MetersPerSecond), + m_rearRightSpeedSetpoint.in(MetersPerSecond))); } - - m_prevTime = curTime; - m_prevSpeeds = targetWheelSpeeds; } @Override diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java index 050e97048d8..b73deba668e 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java @@ -4,6 +4,8 @@ package edu.wpi.first.wpilibj2.command; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.Volts; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.math.controller.PIDController; @@ -14,6 +16,9 @@ import edu.wpi.first.math.kinematics.DifferentialDriveKinematics; import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds; import edu.wpi.first.math.trajectory.Trajectory; +import edu.wpi.first.units.Distance; +import edu.wpi.first.units.MutableMeasure; +import edu.wpi.first.units.Velocity; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.wpilibj.Timer; import java.util.function.BiConsumer; @@ -46,6 +51,14 @@ public class RamseteCommand extends Command { private final PIDController m_rightController; private final BiConsumer m_output; private DifferentialDriveWheelSpeeds m_prevSpeeds = new DifferentialDriveWheelSpeeds(); + private final MutableMeasure> m_prevLeftSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); + private final MutableMeasure> m_prevRightSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); + private final MutableMeasure> m_leftSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); + private final MutableMeasure> m_rightSpeedSetpoint = + MutableMeasure.zero(MetersPerSecond); private double m_prevTime; /** @@ -149,6 +162,8 @@ public void initialize() { initialState.velocityMetersPerSecond, 0, initialState.curvatureRadPerMeter * initialState.velocityMetersPerSecond)); + m_prevLeftSpeedSetpoint.mut_setMagnitude(m_prevSpeeds.leftMetersPerSecond); + m_prevRightSpeedSetpoint.mut_setMagnitude(m_prevSpeeds.rightMetersPerSecond); m_timer.restart(); if (m_usePID) { m_leftController.reset(); @@ -159,7 +174,6 @@ public void initialize() { @Override public void execute() { double curTime = m_timer.get(); - double dt = curTime - m_prevTime; if (m_prevTime < 0) { m_output.accept(0.0, 0.0); @@ -174,17 +188,18 @@ public void execute() { var leftSpeedSetpoint = targetWheelSpeeds.leftMetersPerSecond; var rightSpeedSetpoint = targetWheelSpeeds.rightMetersPerSecond; + m_leftSpeedSetpoint.mut_setMagnitude(targetWheelSpeeds.leftMetersPerSecond); + m_rightSpeedSetpoint.mut_setMagnitude(targetWheelSpeeds.rightMetersPerSecond); + double leftOutput; double rightOutput; if (m_usePID) { double leftFeedforward = - m_feedforward.calculate( - leftSpeedSetpoint, (leftSpeedSetpoint - m_prevSpeeds.leftMetersPerSecond) / dt); + m_feedforward.calculate(m_prevLeftSpeedSetpoint, m_leftSpeedSetpoint).in(Volts); double rightFeedforward = - m_feedforward.calculate( - rightSpeedSetpoint, (rightSpeedSetpoint - m_prevSpeeds.rightMetersPerSecond) / dt); + m_feedforward.calculate(m_prevRightSpeedSetpoint, m_rightSpeedSetpoint).in(Volts); leftOutput = leftFeedforward diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp index 6059db4ecee..c22ac99ce8a 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp @@ -159,7 +159,6 @@ void MecanumControllerCommand::Initialize() { void MecanumControllerCommand::Execute() { auto curTime = m_timer.Get(); - auto dt = curTime - m_prevTime; auto m_desiredState = m_trajectory.Sample(curTime); @@ -175,21 +174,17 @@ void MecanumControllerCommand::Execute() { auto rearRightSpeedSetpoint = targetWheelSpeeds.rearRight; if (m_usePID) { - auto frontLeftFeedforward = m_feedforward.Calculate( - frontLeftSpeedSetpoint, - (frontLeftSpeedSetpoint - m_prevSpeeds.frontLeft) / dt); + auto frontLeftFeedforward = + m_feedforward.Calculate(m_prevSpeeds.frontLeft, frontLeftSpeedSetpoint); - auto rearLeftFeedforward = m_feedforward.Calculate( - rearLeftSpeedSetpoint, - (rearLeftSpeedSetpoint - m_prevSpeeds.rearLeft) / dt); + auto rearLeftFeedforward = + m_feedforward.Calculate(m_prevSpeeds.rearLeft, rearLeftSpeedSetpoint); auto frontRightFeedforward = m_feedforward.Calculate( - frontRightSpeedSetpoint, - (frontRightSpeedSetpoint - m_prevSpeeds.frontRight) / dt); + m_prevSpeeds.frontRight, frontRightSpeedSetpoint); - auto rearRightFeedforward = m_feedforward.Calculate( - rearRightSpeedSetpoint, - (rearRightSpeedSetpoint - m_prevSpeeds.rearRight) / dt); + auto rearRightFeedforward = + m_feedforward.Calculate(m_prevSpeeds.rearRight, rearRightSpeedSetpoint); auto frontLeftOutput = units::volt_t{m_frontLeftController->Calculate( m_currentWheelSpeeds().frontLeft.value(), diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp index b78b6ad4c1c..e0da8c8eaa4 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp @@ -68,7 +68,6 @@ void RamseteCommand::Initialize() { void RamseteCommand::Execute() { auto curTime = m_timer.Get(); - auto dt = curTime - m_prevTime; if (m_prevTime < 0_s) { if (m_usePID) { @@ -85,13 +84,11 @@ void RamseteCommand::Execute() { m_controller.Calculate(m_pose(), m_trajectory.Sample(curTime))); if (m_usePID) { - auto leftFeedforward = m_feedforward.Calculate( - targetWheelSpeeds.left, - (targetWheelSpeeds.left - m_prevSpeeds.left) / dt); + auto leftFeedforward = + m_feedforward.Calculate(m_prevSpeeds.left, targetWheelSpeeds.left); - auto rightFeedforward = m_feedforward.Calculate( - targetWheelSpeeds.right, - (targetWheelSpeeds.right - m_prevSpeeds.right) / dt); + auto rightFeedforward = + m_feedforward.Calculate(m_prevSpeeds.right, targetWheelSpeeds.right); auto leftOutput = units::volt_t{m_leftController->Calculate( diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp index 5d65a5aa360..3be3379683e 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp @@ -40,8 +40,7 @@ class Robot : public frc::TimedRobot { m_motor.SetSetpoint( ExampleSmartMotorController::PIDMode::kPosition, m_setpoint.position.value(), - m_feedforward.Calculate(m_setpoint.velocity, next.velocity, kDt) / - 12_V); + m_feedforward.Calculate(m_setpoint.velocity, next.velocity) / 12_V); m_setpoint = next; } diff --git a/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp index c8e84fb0eef..a29d1699528 100644 --- a/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp @@ -54,9 +54,10 @@ class Robot : public frc::TimedRobot { // accelerate the shooter wheel .IfHigh([&shooter = m_shooter, &controller = m_controller, &ff = m_ff, &encoder = m_shooterEncoder] { - shooter.SetVoltage(units::volt_t{controller.Calculate( - encoder.GetRate(), SHOT_VELOCITY.value())} + - ff.Calculate(SHOT_VELOCITY)); + shooter.SetVoltage( + units::volt_t{controller.Calculate(encoder.GetRate(), + SHOT_VELOCITY.value())} + + ff.Calculate(units::radians_per_second_t{SHOT_VELOCITY})); }); // if not, stop (!shootTrigger).IfHigh([&shooter = m_shooter] { shooter.Set(0.0); }); diff --git a/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp index 047f01a1d1d..6763e7f97c2 100644 --- a/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp @@ -11,6 +11,7 @@ #include #include #include +#include #include /** diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/ShooterSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/ShooterSubsystem.cpp index cff73dac446..297ccc1eaaa 100644 --- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/ShooterSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/ShooterSubsystem.cpp @@ -5,6 +5,7 @@ #include "subsystems/ShooterSubsystem.h" #include +#include #include "Constants.h" diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java index adc52e2ef67..b351d169db4 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.differentialdrivebot; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.kinematics.ChassisSpeeds; @@ -79,8 +82,10 @@ public Drivetrain() { * @param speeds The desired wheel speeds. */ public void setSpeeds(DifferentialDriveWheelSpeeds speeds) { - final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond); - final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond); + final double leftFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.leftMetersPerSecond)).in(Volts); + final double rightFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.rightMetersPerSecond)).in(Volts); final double leftOutput = m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java index 4fc38ca525f..40fd72700a0 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.differentialdriveposeestimator; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.math.ComputerVisionUtil; @@ -139,8 +142,10 @@ public Drivetrain(DoubleArrayTopic cameraToObjectTopic) { * @param speeds The desired wheel speeds. */ public void setSpeeds(DifferentialDriveWheelSpeeds speeds) { - final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond); - final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond); + final double leftFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.leftMetersPerSecond)).in(Volts); + final double rightFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.rightMetersPerSecond)).in(Volts); final double leftOutput = m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java index 59d700bb1ed..e2a66a64e17 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.util.sendable.SendableRegistry; @@ -75,11 +78,11 @@ public void setDriveStates(TrapezoidProfile.State left, TrapezoidProfile.State r m_leftLeader.setSetpoint( ExampleSmartMotorController.PIDMode.kPosition, left.position, - m_feedforward.calculate(left.velocity)); + m_feedforward.calculate(MetersPerSecond.of(left.velocity)).in(Volts)); m_rightLeader.setSetpoint( ExampleSmartMotorController.PIDMode.kPosition, right.position, - m_feedforward.calculate(right.velocity)); + m_feedforward.calculate(MetersPerSecond.of(right.velocity)).in(Volts)); } /** diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/Robot.java index 3aed7b92af8..1bd9c727c43 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/Robot.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.elevatorexponentialprofile; +import static edu.wpi.first.units.Units.RadiansPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.trajectory.ExponentialProfile; import edu.wpi.first.wpilibj.Joystick; @@ -46,7 +49,7 @@ public void teleopPeriodic() { m_motor.setSetpoint( ExampleSmartMotorController.PIDMode.kPosition, m_setpoint.position, - m_feedforward.calculate(m_setpoint.velocity, next.velocity, 0.02) / 12.0); + m_feedforward.calculate(RadiansPerSecond.of(next.velocity)).in(Volts) / 12.0); m_setpoint = next; } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java index 938132ba00d..d451c1377fe 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.elevatortrapezoidprofile; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.wpilibj.Joystick; @@ -46,6 +49,6 @@ public void teleopPeriodic() { m_motor.setSetpoint( ExampleSmartMotorController.PIDMode.kPosition, m_setpoint.position, - m_feedforward.calculate(m_setpoint.velocity) / 12.0); + m_feedforward.calculate(MetersPerSecond.of(m_setpoint.velocity)).in(Volts) / 12.0); } } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java index 08de65c5919..63efa633519 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.eventloop; +import static edu.wpi.first.units.Units.RPM; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.wpilibj.Encoder; @@ -61,10 +64,12 @@ public void robotInit() { shootTrigger // accelerate the shooter wheel .ifHigh( - () -> - m_shooter.setVoltage( - m_controller.calculate(m_shooterEncoder.getRate(), SHOT_VELOCITY) - + m_ff.calculate(SHOT_VELOCITY))); + () -> { + m_shooter.setVoltage( + m_controller.calculate(m_shooterEncoder.getRate(), SHOT_VELOCITY) + + m_ff.calculate(RPM.of(SHOT_VELOCITY)).in(Volts)); + }); + // if not, stop shootTrigger.negate().ifHigh(m_shooter::stopMotor); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java index 3bd0542904c..e4732131875 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.flywheelbangbangcontroller; +import static edu.wpi.first.units.Units.RadiansPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.BangBangController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.numbers.N1; @@ -87,7 +90,8 @@ public void teleopPeriodic() { // Controls a motor with the output of the BangBang controller and a // feedforward. The feedforward is reduced slightly to avoid overspeeding // the shooter. - m_flywheelMotor.setVoltage(bangOutput + 0.9 * m_feedforward.calculate(setpoint)); + m_flywheelMotor.setVoltage( + bangOutput + 0.9 * m_feedforward.calculate(RadiansPerSecond.of(setpoint)).in(Volts)); } /** Update our simulation. This should be run every robot loop in simulation. */ diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/ShooterSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/ShooterSubsystem.java index f6f85f700a0..a8f644d52ee 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/ShooterSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/ShooterSubsystem.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.frisbeebot.subsystems; +import static edu.wpi.first.units.Units.RadiansPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.wpilibj.Encoder; @@ -33,7 +36,11 @@ public ShooterSubsystem() { @Override public void useOutput(double output, double setpoint) { - m_shooterMotor.setVoltage(output + m_shooterFeedforward.calculate(setpoint)); + m_shooterMotor.setVoltage( + output + + m_shooterFeedforward + .calculate(RadiansPerSecond.of(ShooterConstants.kShooterTargetRPS)) + .in(Volts)); } @Override diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java index c64c9b3958a..e00abf6d302 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.mecanumbot; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.geometry.Translation2d; @@ -95,10 +98,14 @@ public MecanumDriveWheelPositions getCurrentDistances() { * @param speeds The desired wheel speeds. */ public void setSpeeds(MecanumDriveWheelSpeeds speeds) { - final double frontLeftFeedforward = m_feedforward.calculate(speeds.frontLeftMetersPerSecond); - final double frontRightFeedforward = m_feedforward.calculate(speeds.frontRightMetersPerSecond); - final double backLeftFeedforward = m_feedforward.calculate(speeds.rearLeftMetersPerSecond); - final double backRightFeedforward = m_feedforward.calculate(speeds.rearRightMetersPerSecond); + final double frontLeftFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.frontLeftMetersPerSecond)).in(Volts); + final double frontRightFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.frontRightMetersPerSecond)).in(Volts); + final double backLeftFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.rearLeftMetersPerSecond)).in(Volts); + final double backRightFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.rearRightMetersPerSecond)).in(Volts); final double frontLeftOutput = m_frontLeftPIDController.calculate( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java index a534ae31b0e..a660c2b07ba 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.mecanumdriveposeestimator; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; @@ -107,10 +110,14 @@ public MecanumDriveWheelPositions getCurrentDistances() { * @param speeds The desired wheel speeds. */ public void setSpeeds(MecanumDriveWheelSpeeds speeds) { - final double frontLeftFeedforward = m_feedforward.calculate(speeds.frontLeftMetersPerSecond); - final double frontRightFeedforward = m_feedforward.calculate(speeds.frontRightMetersPerSecond); - final double backLeftFeedforward = m_feedforward.calculate(speeds.rearLeftMetersPerSecond); - final double backRightFeedforward = m_feedforward.calculate(speeds.rearRightMetersPerSecond); + final double frontLeftFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.frontLeftMetersPerSecond)).in(Volts); + final double frontRightFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.frontRightMetersPerSecond)).in(Volts); + final double backLeftFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.rearLeftMetersPerSecond)).in(Volts); + final double backRightFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.rearRightMetersPerSecond)).in(Volts); final double frontLeftOutput = m_frontLeftPIDController.calculate( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java index d282c2062cf..88d564beb3c 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java @@ -4,6 +4,8 @@ package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems; +import static edu.wpi.first.units.Units.RotationsPerSecond; +import static edu.wpi.first.units.Units.Volts; import static edu.wpi.first.wpilibj2.command.Commands.parallel; import static edu.wpi.first.wpilibj2.command.Commands.waitUntil; @@ -54,11 +56,15 @@ public Command shootCommand(double setpointRotationsPerSecond) { return parallel( // Run the shooter flywheel at the desired setpoint using feedforward and feedback run( - () -> - m_shooterMotor.set( - m_shooterFeedforward.calculate(setpointRotationsPerSecond) - + m_shooterFeedback.calculate( - m_shooterEncoder.getRate(), setpointRotationsPerSecond))), + () -> { + m_shooterMotor.set( + m_shooterFeedforward + .calculate(RotationsPerSecond.of(setpointRotationsPerSecond)) + .in(Volts) + + m_shooterFeedback.calculate( + m_shooterEncoder.getRate(), setpointRotationsPerSecond)); + }), + // Wait until the shooter has reached the setpoint, and then run the feeder waitUntil(m_shooterFeedback::atSetpoint).andThen(() -> m_feederMotor.set(1))) .withName("Shoot"); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java index a69839bc7e7..eb911054a58 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.simpledifferentialdrivesimulation; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.geometry.Pose2d; @@ -94,8 +97,10 @@ public Drivetrain() { /** Sets speeds to the drivetrain motors. */ public void setSpeeds(DifferentialDriveWheelSpeeds speeds) { - var leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond); - var rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond); + final double leftFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.leftMetersPerSecond)).in(Volts); + final double rightFeedforward = + m_feedforward.calculate(MetersPerSecond.of(speeds.rightMetersPerSecond)).in(Volts); double leftOutput = m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond); double rightOutput = diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java index c168860c99b..32ca8fdbbc6 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java @@ -4,6 +4,10 @@ package edu.wpi.first.wpilibj.examples.swervebot; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.RadiansPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.ProfiledPIDController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; @@ -119,17 +123,21 @@ public void setDesiredState(SwerveModuleState desiredState) { state.speedMetersPerSecond *= state.angle.minus(encoderRotation).getCos(); // Calculate the drive output from the drive PID controller. + final double driveOutput = m_drivePIDController.calculate(m_driveEncoder.getRate(), state.speedMetersPerSecond); - final double driveFeedforward = m_driveFeedforward.calculate(state.speedMetersPerSecond); + final double driveFeedforward = + m_driveFeedforward.calculate(MetersPerSecond.of(state.speedMetersPerSecond)).in(Volts); // Calculate the turning motor output from the turning PID controller. final double turnOutput = m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians()); final double turnFeedforward = - m_turnFeedforward.calculate(m_turningPIDController.getSetpoint().velocity); + m_turnFeedforward + .calculate(RadiansPerSecond.of(m_turningPIDController.getSetpoint().velocity)) + .in(Volts); m_driveMotor.setVoltage(driveOutput + driveFeedforward); m_turningMotor.setVoltage(turnOutput + turnFeedforward); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java index 8ee8f4b07b8..f42e1f43996 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java @@ -4,6 +4,10 @@ package edu.wpi.first.wpilibj.examples.swervedriveposeestimator; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.RadiansPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.ProfiledPIDController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; @@ -122,14 +126,17 @@ public void setDesiredState(SwerveModuleState desiredState) { final double driveOutput = m_drivePIDController.calculate(m_driveEncoder.getRate(), state.speedMetersPerSecond); - final double driveFeedforward = m_driveFeedforward.calculate(state.speedMetersPerSecond); + final double driveFeedforward = + m_driveFeedforward.calculate(MetersPerSecond.of(state.speedMetersPerSecond)).in(Volts); // Calculate the turning motor output from the turning PID controller. final double turnOutput = m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians()); final double turnFeedforward = - m_turnFeedforward.calculate(m_turningPIDController.getSetpoint().velocity); + m_turnFeedforward + .calculate(RadiansPerSecond.of(m_turningPIDController.getSetpoint().velocity)) + .in(Volts); m_driveMotor.setVoltage(driveOutput + driveFeedforward); m_turningMotor.setVoltage(turnOutput + turnFeedforward); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/subsystems/Shooter.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/subsystems/Shooter.java index 322df8e1390..94574424db9 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/subsystems/Shooter.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/subsystems/Shooter.java @@ -98,7 +98,9 @@ public Command runShooter(DoubleSupplier shooterSpeed) { return run(() -> { m_shooterMotor.setVoltage( m_shooterFeedback.calculate(m_shooterEncoder.getRate(), shooterSpeed.getAsDouble()) - + m_shooterFeedforward.calculate(shooterSpeed.getAsDouble())); + + m_shooterFeedforward + .calculate(RotationsPerSecond.of(shooterSpeed.getAsDouble())) + .in(Volts)); m_feederMotor.set(ShooterConstants.kFeederSpeed); }) .finallyDo( diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java index eeb76db3196..60accdadf2b 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java @@ -4,9 +4,12 @@ package edu.wpi.first.math.controller; -import edu.wpi.first.math.MatBuilder; -import edu.wpi.first.math.Nat; -import edu.wpi.first.math.system.plant.LinearSystemId; +import static edu.wpi.first.units.Units.Volts; + +import edu.wpi.first.units.Measure; +import edu.wpi.first.units.Unit; +import edu.wpi.first.units.Velocity; +import edu.wpi.first.units.Voltage; /** A helper class that computes feedforward outputs for a simple permanent-magnet DC motor. */ public class SimpleMotorFeedforward { @@ -19,17 +22,22 @@ public class SimpleMotorFeedforward { /** The acceleration gain. */ public final double ka; + /** The period. */ + private double m_dt; + /** - * Creates a new SimpleMotorFeedforward with the specified gains. Units of the gain values will - * dictate units of the computed feedforward. + * Creates a new SimpleMotorFeedforward with the specified gains and period. Units of the gain + * values will dictate units of the computed feedforward. * * @param ks The static gain. * @param kv The velocity gain. * @param ka The acceleration gain. + * @param dtSeconds The period in seconds. * @throws IllegalArgumentException for kv < zero. * @throws IllegalArgumentException for ka < zero. + * @throws IllegalArgumentException for period ≤ zero. */ - public SimpleMotorFeedforward(double ks, double kv, double ka) { + public SimpleMotorFeedforward(double ks, double kv, double ka, double dtSeconds) { this.ks = ks; this.kv = kv; this.ka = ka; @@ -39,17 +47,37 @@ public SimpleMotorFeedforward(double ks, double kv, double ka) { if (ka < 0.0) { throw new IllegalArgumentException("ka must be a non-negative number, got " + ka + "!"); } + if (dtSeconds <= 0.0) { + throw new IllegalArgumentException( + "period must be a positive number, got " + dtSeconds + "!"); + } + m_dt = dtSeconds; + } + + /** + * Creates a new SimpleMotorFeedforward with the specified gains and period. The period is + * defaulted to 20 ms. Units of the gain values will dictate units of the computed feedforward. + * + * @param ks The static gain. + * @param kv The velocity gain. + * @param ka The acceleration gain. + * @throws IllegalArgumentException for kv < zero. + * @throws IllegalArgumentException for ka < zero. + */ + public SimpleMotorFeedforward(double ks, double kv, double ka) { + this(ks, kv, ka, 0.020); } /** * Creates a new SimpleMotorFeedforward with the specified gains. Acceleration gain is defaulted - * to zero. Units of the gain values will dictate units of the computed feedforward. + * to zero. The period is defaulted to 20 ms. Units of the gain values will dictate units of the + * computed feedforward. * * @param ks The static gain. * @param kv The velocity gain. */ public SimpleMotorFeedforward(double ks, double kv) { - this(ks, kv, 0); + this(ks, kv, 0, 0.020); } /** @@ -58,41 +86,112 @@ public SimpleMotorFeedforward(double ks, double kv) { * @param velocity The velocity setpoint. * @param acceleration The acceleration setpoint. * @return The computed feedforward. + * @deprecated Use the current/next velocity overload instead. */ + @SuppressWarnings("removal") + @Deprecated(forRemoval = true, since = "2025") public double calculate(double velocity, double acceleration) { return ks * Math.signum(velocity) + kv * velocity + ka * acceleration; } /** - * Calculates the feedforward from the gains and setpoints. + * Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be + * zero). * - * @param currentVelocity The current velocity setpoint. - * @param nextVelocity The next velocity setpoint. - * @param dtSeconds Time between velocity setpoints in seconds. + * @param velocity The velocity setpoint. * @return The computed feedforward. + * @deprecated Use the current/next velocity overload instead. */ - public double calculate(double currentVelocity, double nextVelocity, double dtSeconds) { - var plant = LinearSystemId.identifyVelocitySystem(this.kv, this.ka); - var feedforward = new LinearPlantInversionFeedforward<>(plant, dtSeconds); - - var r = MatBuilder.fill(Nat.N1(), Nat.N1(), currentVelocity); - var nextR = MatBuilder.fill(Nat.N1(), Nat.N1(), nextVelocity); - - return ks * Math.signum(currentVelocity) + feedforward.calculate(r, nextR).get(0, 0); + @SuppressWarnings("removal") + @Deprecated(forRemoval = true, since = "2025") + public double calculate(double velocity) { + return calculate(velocity, 0); } - // Rearranging the main equation from the calculate() method yields the - // formulas for the methods below: + /** + * Calculates the feedforward from the gains and setpoints assuming discrete control when the + * setpoint does not change. + * + * @param The velocity parameter either as distance or angle. + * @param setpoint The velocity setpoint. + * @return The computed feedforward. + */ + public > Measure calculate(Measure> setpoint) { + return calculate(setpoint, setpoint); + } /** - * Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be - * zero). + * Calculates the feedforward from the gains and setpoints assuming discrete control. * - * @param velocity The velocity setpoint. + * @param The velocity parameter either as distance or angle. + * @param currentVelocity The current velocity setpoint. + * @param nextVelocity The next velocity setpoint. * @return The computed feedforward. */ - public double calculate(double velocity) { - return calculate(velocity, 0); + public > Measure calculate( + Measure> currentVelocity, Measure> nextVelocity) { + if (ka == 0.0) { + // Given the following discrete feedforward model + // + // uₖ = B_d⁺(rₖ₊₁ − A_d rₖ) + // + // where + // + // A_d = eᴬᵀ + // B_d = A⁻¹(eᴬᵀ - I)B + // A = −kᵥ/kₐ + // B = 1/kₐ + // + // We want the feedforward model when kₐ = 0. + // + // Simplify A. + // + // A = −kᵥ/kₐ + // + // As kₐ approaches zero, A approaches -∞. + // + // A = −∞ + // + // Simplify A_d. + // + // A_d = eᴬᵀ + // A_d = exp(−∞) + // A_d = 0 + // + // Simplify B_d. + // + // B_d = A⁻¹(eᴬᵀ - I)B + // B_d = A⁻¹((0) - I)B + // B_d = A⁻¹(-I)B + // B_d = -A⁻¹B + // B_d = -(−kᵥ/kₐ)⁻¹(1/kₐ) + // B_d = (kᵥ/kₐ)⁻¹(1/kₐ) + // B_d = kₐ/kᵥ(1/kₐ) + // B_d = 1/kᵥ + // + // Substitute these into the feedforward equation. + // + // uₖ = B_d⁺(rₖ₊₁ − A_d rₖ) + // uₖ = (1/kᵥ)⁺(rₖ₊₁ − (0) rₖ) + // uₖ = kᵥrₖ₊₁ + return Volts.of(ks * Math.signum(nextVelocity.magnitude()) + kv * nextVelocity.magnitude()); + } else { + // uₖ = B_d⁺(rₖ₊₁ − A_d rₖ) + // + // where + // + // A_d = eᴬᵀ + // B_d = A⁻¹(eᴬᵀ - I)B + // A = −kᵥ/kₐ + // B = 1/kₐ + double A = -kv / ka; + double B = 1.0 / ka; + double A_d = Math.exp(A * m_dt); + double B_d = 1.0 / A * (A_d - 1.0) * B; + return Volts.of( + ks * Math.signum(currentVelocity.magnitude()) + + 1.0 / B_d * (nextVelocity.magnitude() - A_d * currentVelocity.magnitude())); + } } /** diff --git a/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h b/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h index cc31fc10582..1ae1af3df35 100644 --- a/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h +++ b/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h @@ -4,16 +4,15 @@ #pragma once +#include #include -#include "frc/EigenCore.h" -#include "frc/controller/LinearPlantInversionFeedforward.h" -#include "frc/system/plant/LinearSystemId.h" #include "units/time.h" #include "units/voltage.h" #include "wpimath/MathShared.h" namespace frc { + /** * A helper class that computes feedforward voltages for a simple * permanent-magnet DC motor. @@ -35,22 +34,40 @@ class SimpleMotorFeedforward { * @param kS The static gain, in volts. * @param kV The velocity gain, in volt seconds per distance. * @param kA The acceleration gain, in volt seconds² per distance. + * @param dt The period in seconds. */ constexpr SimpleMotorFeedforward( units::volt_t kS, units::unit_t kV, - units::unit_t kA = units::unit_t(0)) - : kS(kS), kV(kV), kA(kA) { - if (kV.value() < 0) { - wpi::math::MathSharedStore::ReportError( - "kV must be a non-negative number, got {}!", kV.value()); - kV = units::unit_t{0}; - wpi::math::MathSharedStore::ReportWarning("kV defaulted to 0."); - } - if (kA.value() < 0) { + units::unit_t kA = units::unit_t(0), + units::second_t dt = 20_ms) + : kS(kS), + kV([&] { + if (kV.value() < 0) { + wpi::math::MathSharedStore::ReportError( + "kV must be a non-negative number, got {}!", kV.value()); + wpi::math::MathSharedStore::ReportWarning("kV defaulted to 0."); + return units::unit_t{0}; + } else { + return kV; + } + }()), + kA([&] { + if (kA.value() < 0) { + wpi::math::MathSharedStore::ReportError( + "kA must be a non-negative number, got {}!", kA.value()); + wpi::math::MathSharedStore::ReportWarning("kA defaulted to 0."); + return units::unit_t{0}; + } else { + return kA; + } + }()) { + if (dt <= 0_ms) { wpi::math::MathSharedStore::ReportError( - "kA must be a non-negative number, got {}!", kA.value()); - kA = units::unit_t{0}; - wpi::math::MathSharedStore::ReportWarning("kA defaulted to 0;"); + "period must be a positive number, got {}!", dt.value()); + m_dt = 20_ms; + wpi::math::MathSharedStore::ReportWarning("period defaulted to 20 ms."); + } else { + m_dt = dt; } } @@ -60,33 +77,101 @@ class SimpleMotorFeedforward { * @param velocity The velocity setpoint, in distance per second. * @param acceleration The acceleration setpoint, in distance per second². * @return The computed feedforward, in volts. + * @deprecated Use the current/next velocity overload instead. */ - constexpr units::volt_t Calculate(units::unit_t velocity, - units::unit_t acceleration = - units::unit_t(0)) const { + [[deprecated("Use the current/next velocity overload instead.")]] + constexpr units::volt_t Calculate( + units::unit_t velocity, + units::unit_t acceleration) const { return kS * wpi::sgn(velocity) + kV * velocity + kA * acceleration; } + /** + * Calculates the feedforward from the gains and setpoint. + * Use this method when the setpoint does not change. + * + * @param setpoint The velocity setpoint, in distance per + * second. + * @return The computed feedforward, in volts. + */ + constexpr units::volt_t Calculate(units::unit_t setpoint) const { + return Calculate(setpoint, setpoint); + } + /** * Calculates the feedforward from the gains and setpoints. * * @param currentVelocity The current velocity setpoint, in distance per * second. * @param nextVelocity The next velocity setpoint, in distance per second. - * @param dt Time between velocity setpoints in seconds. * @return The computed feedforward, in volts. */ - units::volt_t Calculate(units::unit_t currentVelocity, - units::unit_t nextVelocity, - units::second_t dt) const { - auto plant = LinearSystemId::IdentifyVelocitySystem(kV, kA); - LinearPlantInversionFeedforward<1, 1> feedforward{plant, dt}; - - Vectord<1> r{currentVelocity.value()}; - Vectord<1> nextR{nextVelocity.value()}; - - return kS * wpi::sgn(currentVelocity.value()) + - units::volt_t{feedforward.Calculate(r, nextR)(0)}; + constexpr units::volt_t Calculate( + units::unit_t currentVelocity, + units::unit_t nextVelocity) const { + if (kA == decltype(kA)(0)) { + // Given the following discrete feedforward model + // + // uₖ = B_d⁺(rₖ₊₁ − A_d rₖ) + // + // where + // + // A_d = eᴬᵀ + // B_d = A⁻¹(eᴬᵀ - I)B + // A = −kᵥ/kₐ + // B = 1/kₐ + // + // We want the feedforward model when kₐ = 0. + // + // Simplify A. + // + // A = −kᵥ/kₐ + // + // As kₐ approaches zero, A approaches -∞. + // + // A = −∞ + // + // Simplify A_d. + // + // A_d = eᴬᵀ + // A_d = std::exp(−∞) + // A_d = 0 + // + // Simplify B_d. + // + // B_d = A⁻¹(eᴬᵀ - I)B + // B_d = A⁻¹((0) - I)B + // B_d = A⁻¹(-I)B + // B_d = -A⁻¹B + // B_d = -(−kᵥ/kₐ)⁻¹(1/kₐ) + // B_d = (kᵥ/kₐ)⁻¹(1/kₐ) + // B_d = kₐ/kᵥ(1/kₐ) + // B_d = 1/kᵥ + // + // Substitute these into the feedforward equation. + // + // uₖ = B_d⁺(rₖ₊₁ − A_d rₖ) + // uₖ = (1/kᵥ)⁺(rₖ₊₁ − (0) rₖ) + // uₖ = kᵥrₖ₊₁ + return kS * wpi::sgn(nextVelocity) + kV * nextVelocity; + } else { + // uₖ = B_d⁺(rₖ₊₁ − A_d rₖ) + // + // where + // + // A_d = eᴬᵀ + // B_d = A⁻¹(eᴬᵀ - I)B + // A = −kᵥ/kₐ + // B = 1/kₐ + double A = -kV.value() / kA.value(); + double B = 1.0 / kA.value(); + double A_d = gcem::exp(A * m_dt.value()); + double B_d = 1.0 / A * (A_d - 1.0) * B; + return kS * wpi::sgn(currentVelocity) + + units::volt_t{ + 1.0 / B_d * + (nextVelocity.value() - A_d * currentVelocity.value())}; + } } // Rearranging the main equation from the calculate() method yields the @@ -168,5 +253,10 @@ class SimpleMotorFeedforward { /** The acceleration gain. */ const units::unit_t kA; + + private: + /** The period. */ + units::second_t m_dt; }; + } // namespace frc diff --git a/wpimath/src/test/java/edu/wpi/first/math/controller/SimpleMotorFeedforwardTest.java b/wpimath/src/test/java/edu/wpi/first/math/controller/SimpleMotorFeedforwardTest.java index 6277c030cf7..9d501edf92a 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/controller/SimpleMotorFeedforwardTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/controller/SimpleMotorFeedforwardTest.java @@ -4,12 +4,14 @@ package edu.wpi.first.math.controller; +import static edu.wpi.first.units.Units.RadiansPerSecond; import static org.junit.jupiter.api.Assertions.assertEquals; import edu.wpi.first.math.MatBuilder; import edu.wpi.first.math.Nat; import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.numbers.N1; +import edu.wpi.first.units.MutableMeasure; import org.junit.jupiter.api.Test; class SimpleMotorFeedforwardTest { @@ -24,22 +26,27 @@ void testCalculate() { var B = MatBuilder.fill(Nat.N1(), Nat.N1(), 1.0 / Ka); var plantInversion = new LinearPlantInversionFeedforward(A, B, dt); - var simpleMotor = new SimpleMotorFeedforward(Ks, Kv, Ka); + var simpleMotor = new SimpleMotorFeedforward(Ks, Kv, Ka, dt); var r = VecBuilder.fill(2.0); var nextR = VecBuilder.fill(3.0); + var currentVelocity = MutableMeasure.ofBaseUnits(2.0, RadiansPerSecond); + var nextVelocity = MutableMeasure.ofBaseUnits(3.0, RadiansPerSecond); - assertEquals(37.52499583432516 + 0.5, simpleMotor.calculate(2.0, 3.0, dt), 0.002); + assertEquals( + 37.52499583432516 + 0.5, + simpleMotor.calculate(currentVelocity, nextVelocity).magnitude(), + 0.002); assertEquals( plantInversion.calculate(r, nextR).get(0, 0) + Ks, - simpleMotor.calculate(2.0, 3.0, dt), + simpleMotor.calculate(currentVelocity, nextVelocity).magnitude(), 0.002); // These won't match exactly. It's just an approximation to make sure they're // in the same ballpark. assertEquals( plantInversion.calculate(r, nextR).get(0, 0) + Ks, - simpleMotor.calculate(2.0, 1.0 / dt), + simpleMotor.calculate(currentVelocity, nextVelocity).magnitude(), 2.0); } } diff --git a/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveVoltageConstraintTest.java b/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveVoltageConstraintTest.java index 1f9d59b7954..1cedcae1de5 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveVoltageConstraintTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveVoltageConstraintTest.java @@ -4,6 +4,8 @@ package edu.wpi.first.math.trajectory; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.Volts; import static org.junit.jupiter.api.Assertions.assertAll; import static org.junit.jupiter.api.Assertions.assertDoesNotThrow; import static org.junit.jupiter.api.Assertions.assertTrue; @@ -41,33 +43,49 @@ void testDifferentialDriveVoltageConstraint() { point.velocityMetersPerSecond, 0, point.velocityMetersPerSecond * point.curvatureRadPerMeter); - var wheelSpeeds = kinematics.toWheelSpeeds(chassisSpeeds); t += dt; + var acceleration = point.accelerationMetersPerSecondSq; // Not really a strictly-correct test as we're using the chassis accel instead of the // wheel accel, but much easier than doing it "properly" and a reasonable check anyway assertAll( () -> assertTrue( - feedforward.calculate( - wheelSpeeds.leftMetersPerSecond, point.accelerationMetersPerSecondSq) + feedforward + .calculate( + MetersPerSecond.of(wheelSpeeds.leftMetersPerSecond), + MetersPerSecond.of( + wheelSpeeds.leftMetersPerSecond + dt * acceleration)) + .in(Volts) <= maxVoltage + 0.05), () -> assertTrue( - feedforward.calculate( - wheelSpeeds.leftMetersPerSecond, point.accelerationMetersPerSecondSq) + feedforward + .calculate( + MetersPerSecond.of(wheelSpeeds.leftMetersPerSecond), + MetersPerSecond.of( + wheelSpeeds.leftMetersPerSecond + dt * acceleration)) + .in(Volts) >= -maxVoltage - 0.05), () -> assertTrue( - feedforward.calculate( - wheelSpeeds.rightMetersPerSecond, point.accelerationMetersPerSecondSq) + feedforward + .calculate( + MetersPerSecond.of(wheelSpeeds.rightMetersPerSecond), + MetersPerSecond.of( + wheelSpeeds.rightMetersPerSecond + dt * acceleration)) + .in(Volts) <= maxVoltage + 0.05), () -> assertTrue( - feedforward.calculate( - wheelSpeeds.rightMetersPerSecond, point.accelerationMetersPerSecondSq) + feedforward + .calculate( + MetersPerSecond.of(wheelSpeeds.rightMetersPerSecond), + MetersPerSecond.of( + wheelSpeeds.rightMetersPerSecond + dt * acceleration)) + .in(Volts) >= -maxVoltage - 0.05)); } } diff --git a/wpimath/src/test/java/edu/wpi/first/math/trajectory/ExponentialProfileTest.java b/wpimath/src/test/java/edu/wpi/first/math/trajectory/ExponentialProfileTest.java index e9c535e1fb1..6a987d47445 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/trajectory/ExponentialProfileTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/trajectory/ExponentialProfileTest.java @@ -4,19 +4,21 @@ package edu.wpi.first.math.trajectory; +import static edu.wpi.first.units.Units.RadiansPerSecond; import static org.junit.jupiter.api.Assertions.assertAll; import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertNotEquals; import static org.junit.jupiter.api.Assertions.assertTrue; import edu.wpi.first.math.controller.SimpleMotorFeedforward; +import edu.wpi.first.units.MutableMeasure; import java.util.List; import org.junit.jupiter.api.Test; class ExponentialProfileTest { private static final double kDt = 0.01; private static final SimpleMotorFeedforward feedforward = - new SimpleMotorFeedforward(0, 2.5629, 0.43277); + new SimpleMotorFeedforward(0, 2.5629, 0.43277, kDt); private static final ExponentialProfile.Constraints constraints = ExponentialProfile.Constraints.fromCharacteristics(12, 2.5629, 0.43277); @@ -43,10 +45,11 @@ private static void assertNear( private static ExponentialProfile.State checkDynamics( ExponentialProfile profile, ExponentialProfile.State current, ExponentialProfile.State goal) { var next = profile.calculate(kDt, current, goal); + var currentVelocity = MutableMeasure.ofBaseUnits(current.velocity, RadiansPerSecond); + var nextVelocity = MutableMeasure.ofBaseUnits(next.velocity, RadiansPerSecond); + var signal = feedforward.calculate(currentVelocity, nextVelocity); - var signal = feedforward.calculate(current.velocity, next.velocity, kDt); - - assertTrue(Math.abs(signal) < constraints.maxInput + 1e-9); + assertTrue(Math.abs(signal.magnitude()) < constraints.maxInput + 1e-9); return next; } diff --git a/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp b/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp index 78780112271..35d35b8f365 100644 --- a/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp +++ b/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp @@ -12,35 +12,34 @@ #include "units/acceleration.h" #include "units/length.h" #include "units/time.h" +#include "units/velocity.h" namespace frc { TEST(SimpleMotorFeedforwardTest, Calculate) { - double Ks = 0.5; - double Kv = 3.0; - double Ka = 0.6; - auto dt = 0.02_s; + constexpr auto Ks = 0.5_V; + constexpr auto Kv = 3_V / 1_mps; + constexpr auto Ka = 0.6_V / 1_mps_sq; + constexpr units::second_t dt = 20_ms; - Matrixd<1, 1> A{-Kv / Ka}; - Matrixd<1, 1> B{1.0 / Ka}; + constexpr Matrixd<1, 1> A{{-Kv.value() / Ka.value()}}; + constexpr Matrixd<1, 1> B{{1.0 / Ka.value()}}; frc::LinearPlantInversionFeedforward<1, 1> plantInversion{A, B, dt}; - frc::SimpleMotorFeedforward simpleMotor{ - units::volt_t{Ks}, units::volt_t{Kv} / 1_mps, - units::volt_t{Ka} / 1_mps_sq}; + frc::SimpleMotorFeedforward simpleMotor{Ks, Kv, Ka}; - Vectord<1> r{2.0}; - Vectord<1> nextR{3.0}; + constexpr Vectord<1> r{{2.0}}; + constexpr Vectord<1> nextR{{3.0}}; - EXPECT_NEAR(37.524995834325161 + Ks, - simpleMotor.Calculate(2_mps, 3_mps, dt).value(), 0.002); - EXPECT_NEAR(plantInversion.Calculate(r, nextR)(0) + Ks, - simpleMotor.Calculate(2_mps, 3_mps, dt).value(), 0.002); + EXPECT_NEAR((37.524995834325161_V + Ks).value(), + simpleMotor.Calculate(2_mps, 3_mps).value(), 0.002); + EXPECT_NEAR(plantInversion.Calculate(r, nextR)(0) + Ks.value(), + simpleMotor.Calculate(2_mps, 3_mps).value(), 0.002); // These won't match exactly. It's just an approximation to make sure they're // in the same ballpark. - EXPECT_NEAR(plantInversion.Calculate(r, nextR)(0) + Ks, - simpleMotor.Calculate(2_mps, 1_mps / dt).value(), 2.0); + EXPECT_NEAR(plantInversion.Calculate(r, nextR)(0) + Ks.value(), + simpleMotor.Calculate(2_mps, 3_mps).value(), 2.0); } } // namespace frc diff --git a/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp b/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp index 5282638ad02..6c603854896 100644 --- a/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp @@ -45,17 +45,19 @@ TEST(DifferentialDriveVoltageConstraintTest, Constraint) { point.velocity * point.curvature}; auto [left, right] = kinematics.ToWheelSpeeds(chassisSpeeds); - + auto acceleration = point.acceleration; // Not really a strictly-correct test as we're using the chassis accel // instead of the wheel accel, but much easier than doing it "properly" and // a reasonable check anyway - EXPECT_TRUE(feedforward.Calculate(left, point.acceleration) < + EXPECT_TRUE(feedforward.Calculate(left, left + acceleration * dt) < maxVoltage + 0.05_V); - EXPECT_TRUE(feedforward.Calculate(left, point.acceleration) > + EXPECT_TRUE(feedforward.Calculate(left, left + acceleration * dt) > -maxVoltage - 0.05_V); - EXPECT_TRUE(feedforward.Calculate(right, point.acceleration) < + EXPECT_TRUE(feedforward.Calculate(right, + + right + acceleration * dt) < maxVoltage + 0.05_V); - EXPECT_TRUE(feedforward.Calculate(right, point.acceleration) > + EXPECT_TRUE(feedforward.Calculate(right, right + acceleration * dt) > -maxVoltage - 0.05_V); } } diff --git a/wpimath/src/test/native/cpp/trajectory/ExponentialProfileTest.cpp b/wpimath/src/test/native/cpp/trajectory/ExponentialProfileTest.cpp index 8df3aa1e4b1..663ed3af09d 100644 --- a/wpimath/src/test/native/cpp/trajectory/ExponentialProfileTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/ExponentialProfileTest.cpp @@ -41,9 +41,9 @@ frc::ExponentialProfile::State CheckDynamics( frc::ExponentialProfile::State current, frc::ExponentialProfile::State goal) { auto next = profile.Calculate(kDt, current, goal); - auto signal = feedforward.Calculate(current.velocity, next.velocity, kDt); + auto signal = feedforward.Calculate(current.velocity, next.velocity); - EXPECT_LE(units::math::abs(signal), constraints.maxInput + 1e-9_V); + EXPECT_LE(units::math::abs(signal), (constraints.maxInput + 1e-9_V)); return next; } @@ -52,8 +52,8 @@ TEST(ExponentialProfileTest, ReachesGoal) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{10_m, 0_mps}; frc::ExponentialProfile::State state{0_m, 0_mps}; @@ -69,8 +69,8 @@ TEST(ExponentialProfileTest, PosContinousUnderVelChange) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{10_m, 0_mps}; frc::ExponentialProfile::State state{0_m, 0_mps}; @@ -92,8 +92,8 @@ TEST(ExponentialProfileTest, PosContinousUnderVelChangeBackward) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{-10_m, 0_mps}; frc::ExponentialProfile::State state{0_m, 0_mps}; @@ -114,8 +114,8 @@ TEST(ExponentialProfileTest, Backwards) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{-10_m, 0_mps}; frc::ExponentialProfile::State state; @@ -129,8 +129,8 @@ TEST(ExponentialProfileTest, SwitchGoalInMiddle) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{-10_m, 0_mps}; frc::ExponentialProfile::State state{0_m, 0_mps}; @@ -151,8 +151,8 @@ TEST(ExponentialProfileTest, TopSpeed) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{40_m, 0_mps}; frc::ExponentialProfile::State state; @@ -172,8 +172,8 @@ TEST(ExponentialProfileTest, TopSpeedBackward) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{-40_m, 0_mps}; frc::ExponentialProfile::State state; @@ -193,8 +193,8 @@ TEST(ExponentialProfileTest, HighInitialSpeed) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{40_m, 0_mps}; frc::ExponentialProfile::State state{0_m, 8_mps}; @@ -210,8 +210,8 @@ TEST(ExponentialProfileTest, HighInitialSpeedBackward) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{-40_m, 0_mps}; frc::ExponentialProfile::State state{0_m, -8_mps}; @@ -278,8 +278,8 @@ TEST(ExponentialProfileTest, TimingToCurrent) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{2_m, 0_mps}; frc::ExponentialProfile::State state{0_m, 0_mps}; @@ -295,8 +295,8 @@ TEST(ExponentialProfileTest, TimingToGoal) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{2_m, 0_mps}; frc::ExponentialProfile::State state{0_m, 0_mps}; @@ -318,8 +318,8 @@ TEST(ExponentialProfileTest, TimingToNegativeGoal) { frc::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{0_V, 2.5629_V / 1_mps, - 0.43277_V / 1_mps_sq}; + frc::SimpleMotorFeedforward feedforward{ + 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; frc::ExponentialProfile::State goal{-2_m, 0_mps}; frc::ExponentialProfile::State state{0_m, 0_mps}; From 59256f0e00f2aba1e300ca142338caf573a1cc37 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 16 Jul 2024 20:25:43 -0400 Subject: [PATCH 06/10] [epilogue] Add an annotation-based logging framework for Java programs (#6584) --- docs/build.gradle | 2 + epilogue-processor/build.gradle | 19 + .../processor/AnnotationProcessor.java | 413 ++++++ .../epilogue/processor/ArrayHandler.java | 75 ++ .../epilogue/processor/CollectionHandler.java | 57 + .../processor/ConfiguredLoggerHandler.java | 41 + .../epilogue/processor/ElementHandler.java | 136 ++ .../first/epilogue/processor/EnumHandler.java | 33 + .../epilogue/processor/EpilogueGenerator.java | 172 +++ .../epilogue/processor/LoggableHandler.java | 43 + .../epilogue/processor/LoggerGenerator.java | 245 ++++ .../epilogue/processor/MeasureHandler.java | 37 + .../epilogue/processor/PrimitiveHandler.java | 41 + .../epilogue/processor/SendableHandler.java | 56 + .../first/epilogue/processor/StringUtils.java | 110 ++ .../epilogue/processor/StructHandler.java | 50 + .../epilogue/processor/SupplierHandler.java | 67 + .../processor/AnnotationProcessorTest.java | 1172 +++++++++++++++++ .../processor/EpilogueGeneratorTest.java | 326 +++++ .../epilogue/processor/StringUtilsTest.java | 19 + epilogue-runtime/build.gradle | 16 + .../wpi/first/epilogue/CustomLoggerFor.java | 30 + .../first/epilogue/EpilogueConfiguration.java | 43 + .../java/edu/wpi/first/epilogue/Logged.java | 92 ++ .../edu/wpi/first/epilogue/NotLogged.java | 18 + .../epilogue/logging/ClassSpecificLogger.java | 119 ++ .../first/epilogue/logging/DataLogger.java | 229 ++++ .../first/epilogue/logging/FileLogger.java | 144 ++ .../first/epilogue/logging/LazyLogger.java | 240 ++++ .../logging/LogBackedSendableBuilder.java | 212 +++ .../first/epilogue/logging/MultiLogger.java | 134 ++ .../first/epilogue/logging/NTDataLogger.java | 167 +++ .../first/epilogue/logging/NullLogger.java | 62 + .../wpi/first/epilogue/logging/SubLogger.java | 115 ++ .../epilogue/logging/errors/CrashOnError.java | 22 + .../epilogue/logging/errors/ErrorHandler.java | 61 + .../epilogue/logging/errors/ErrorPrinter.java | 19 + .../logging/errors/LoggerDisabler.java | 69 + .../logging/ClassSpecificLoggerTest.java | 44 + .../epilogue/logging/LazyLoggerTest.java | 56 + .../first/epilogue/logging/TestLogger.java | 109 ++ settings.gradle | 2 + shared/java/javacommon.gradle | 2 + wpilibjExamples/build.gradle | 2 + .../RapidReactCommandBot.java | 2 + .../examples/rapidreactcommandbot/Robot.java | 8 + .../subsystems/Drive.java | 4 + .../subsystems/Intake.java | 2 + .../subsystems/Pneumatics.java | 10 +- .../subsystems/Shooter.java | 2 + .../subsystems/Storage.java | 5 + 51 files changed, 5147 insertions(+), 7 deletions(-) create mode 100644 epilogue-processor/build.gradle create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/AnnotationProcessor.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ArrayHandler.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/CollectionHandler.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ConfiguredLoggerHandler.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ElementHandler.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EnumHandler.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EpilogueGenerator.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/LoggableHandler.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/LoggerGenerator.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/MeasureHandler.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/PrimitiveHandler.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/SendableHandler.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/StringUtils.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/StructHandler.java create mode 100644 epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/SupplierHandler.java create mode 100644 epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/AnnotationProcessorTest.java create mode 100644 epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/EpilogueGeneratorTest.java create mode 100644 epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/StringUtilsTest.java create mode 100644 epilogue-runtime/build.gradle create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/CustomLoggerFor.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/Logged.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/NotLogged.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/ClassSpecificLogger.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/DataLogger.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/FileLogger.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LazyLogger.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LogBackedSendableBuilder.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/MultiLogger.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NTDataLogger.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NullLogger.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/SubLogger.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/CrashOnError.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorHandler.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorPrinter.java create mode 100644 epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/LoggerDisabler.java create mode 100644 epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/ClassSpecificLoggerTest.java create mode 100644 epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/LazyLoggerTest.java create mode 100644 epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/TestLogger.java diff --git a/docs/build.gradle b/docs/build.gradle index fa07e96b06d..49b8f4cf7d2 100644 --- a/docs/build.gradle +++ b/docs/build.gradle @@ -6,6 +6,7 @@ plugins { evaluationDependsOn(':apriltag') evaluationDependsOn(':cameraserver') evaluationDependsOn(':cscore') +evaluationDependsOn(':epilogue-runtime') evaluationDependsOn(':hal') evaluationDependsOn(':ntcore') evaluationDependsOn(':wpilibNewCommands') @@ -234,6 +235,7 @@ task generateJavaDocs(type: Javadoc) { source project(':apriltag').sourceSets.main.java source project(':cameraserver').sourceSets.main.java source project(':cscore').sourceSets.main.java + source project(':epilogue-runtime').sourceSets.main.java source project(':hal').sourceSets.main.java source project(':ntcore').sourceSets.main.java source project(':wpilibNewCommands').sourceSets.main.java diff --git a/epilogue-processor/build.gradle b/epilogue-processor/build.gradle new file mode 100644 index 00000000000..a3dcc8d07cc --- /dev/null +++ b/epilogue-processor/build.gradle @@ -0,0 +1,19 @@ +ext { + useJava = true + useCpp = false + baseId = 'epilogue-processor' + groupId = 'edu.wpi.first.epilogue' + + devMain = '' +} + +apply from: "${rootDir}/shared/java/javacommon.gradle" + +dependencies { + implementation(project(':epilogue-runtime')) + api project(':wpilibNewCommands') + + implementation 'com.google.auto.service:auto-service:1.1.1' + annotationProcessor 'com.google.auto.service:auto-service:1.1.1' + testImplementation 'com.google.testing.compile:compile-testing:+' +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/AnnotationProcessor.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/AnnotationProcessor.java new file mode 100644 index 00000000000..5626c341dc0 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/AnnotationProcessor.java @@ -0,0 +1,413 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import com.google.auto.service.AutoService; +import edu.wpi.first.epilogue.CustomLoggerFor; +import edu.wpi.first.epilogue.Logged; +import edu.wpi.first.epilogue.NotLogged; +import java.io.IOException; +import java.util.ArrayList; +import java.util.Comparator; +import java.util.HashMap; +import java.util.List; +import java.util.Map; +import java.util.Set; +import javax.annotation.processing.AbstractProcessor; +import javax.annotation.processing.Processor; +import javax.annotation.processing.RoundEnvironment; +import javax.annotation.processing.SupportedAnnotationTypes; +import javax.annotation.processing.SupportedSourceVersion; +import javax.lang.model.SourceVersion; +import javax.lang.model.element.AnnotationMirror; +import javax.lang.model.element.AnnotationValue; +import javax.lang.model.element.Element; +import javax.lang.model.element.ElementKind; +import javax.lang.model.element.ExecutableElement; +import javax.lang.model.element.Modifier; +import javax.lang.model.element.TypeElement; +import javax.lang.model.element.VariableElement; +import javax.lang.model.type.DeclaredType; +import javax.lang.model.type.NoType; +import javax.lang.model.type.TypeKind; +import javax.lang.model.type.TypeMirror; +import javax.tools.Diagnostic; + +@SupportedAnnotationTypes({ + "edu.wpi.first.epilogue.CustomLoggerFor", + "edu.wpi.first.epilogue.Logged" +}) +@SupportedSourceVersion(SourceVersion.RELEASE_17) +@AutoService(Processor.class) +public class AnnotationProcessor extends AbstractProcessor { + private static final String kCustomLoggerFqn = "edu.wpi.first.epilogue.CustomLoggerFor"; + private static final String kClassSpecificLoggerFqn = + "edu.wpi.first.epilogue.logging.ClassSpecificLogger"; + private static final String kLoggedFqn = "edu.wpi.first.epilogue.Logged"; + + private EpilogueGenerator m_epiloguerGenerator; + private LoggerGenerator m_loggerGenerator; + private List m_handlers; + + @Override + public boolean process(Set annotations, RoundEnvironment roundEnv) { + if (annotations.isEmpty()) { + // Nothing to do, don't claim + return false; + } + + Map customLoggers = new HashMap<>(); + + annotations.stream() + .filter(ann -> kCustomLoggerFqn.contentEquals(ann.getQualifiedName())) + .findAny() + .ifPresent( + customLogger -> { + customLoggers.putAll(processCustomLoggers(roundEnv, customLogger)); + }); + + roundEnv.getRootElements().stream() + .filter( + e -> + processingEnv + .getTypeUtils() + .isAssignable( + e.asType(), + processingEnv + .getTypeUtils() + .erasure( + processingEnv + .getElementUtils() + .getTypeElement(kClassSpecificLoggerFqn) + .asType()))) + .filter(e -> e.getAnnotation(CustomLoggerFor.class) == null) + .forEach( + e -> { + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, + "Custom logger classes should have a @CustomLoggerFor annotation", + e); + }); + + // Handlers are declared in order of priority. If an element could be logged in more than one + // way (eg a class implements both Sendable and StructSerializable), the order of the handlers + // in this list will determine how it gets logged. + m_handlers = + List.of( + new LoggableHandler(processingEnv), // prioritize epilogue logging over Sendable + new ConfiguredLoggerHandler( + processingEnv, customLoggers), // then customized logging configs + new ArrayHandler(processingEnv), + new CollectionHandler(processingEnv), + new EnumHandler(processingEnv), + new MeasureHandler(processingEnv), + new PrimitiveHandler(processingEnv), + new SupplierHandler(processingEnv), + new StructHandler(processingEnv), // prioritize struct over sendable + new SendableHandler(processingEnv)); + + m_epiloguerGenerator = new EpilogueGenerator(processingEnv, customLoggers); + m_loggerGenerator = new LoggerGenerator(processingEnv, m_handlers); + + annotations.stream() + .filter(ann -> kLoggedFqn.contentEquals(ann.getQualifiedName())) + .findAny() + .ifPresent( + epilogue -> { + processEpilogue(roundEnv, epilogue); + }); + + return false; + } + + private boolean validateFields(Set annotatedElements) { + var fields = + annotatedElements.stream() + .filter(e -> e instanceof VariableElement) + .map(e -> (VariableElement) e) + .toList(); + + boolean valid = true; + + for (VariableElement field : fields) { + // Field is explicitly tagged + // And is not opted out of + if (field.getAnnotation(NotLogged.class) == null && isNotLoggable(field, field.asType())) { + // And is not of a loggable type + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, + "[EPILOGUE] You have opted in to logging on this field, " + + "but it is not a loggable data type!", + field); + valid = false; + } + } + return valid; + } + + private boolean validateMethods(Set annotatedElements) { + var methods = + annotatedElements.stream() + .filter(e -> e instanceof ExecutableElement) + .map(e -> (ExecutableElement) e) + .toList(); + + boolean valid = true; + + for (ExecutableElement method : methods) { + // Field is explicitly tagged + if (method.getAnnotation(NotLogged.class) == null) { + // And is not opted out of + if (isNotLoggable(method, method.getReturnType())) { + // And is not of a loggable type + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, + "[EPILOGUE] You have opted in to logging on this method, " + + "but it does not return a loggable data type!", + method); + valid = false; + } + + if (!method.getModifiers().contains(Modifier.PUBLIC)) { + // Only public methods can be logged + + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, "[EPILOGUE] Logged methods must be public", method); + + valid = false; + } + + if (method.getModifiers().contains(Modifier.STATIC)) { + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, "[EPILOGUE] Logged methods cannot be static", method); + + valid = false; + } + + if (method.getReturnType().getKind() == TypeKind.NONE) { + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, "[EPILOGUE] Logged methods cannot be void", method); + + valid = false; + } + + if (!method.getParameters().isEmpty()) { + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, + "[EPILOGUE] Logged methods cannot accept arguments", + method); + + valid = false; + } + } + } + return valid; + } + + /** + * Checks if a type is not loggable. + * + * @param type the type to check + */ + private boolean isNotLoggable(Element element, TypeMirror type) { + if (type instanceof NoType) { + // e.g. void, cannot log + return true; + } + + boolean loggable = m_handlers.stream().anyMatch(h -> h.isLoggable(element)); + + if (loggable) { + return false; + } + + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.NOTE, + "[EPILOGUE] Excluded from logs because " + type + " is not a loggable data type", + element); + return true; + } + + @SuppressWarnings("unchecked") + private Map processCustomLoggers( + RoundEnvironment roundEnv, TypeElement customLoggerAnnotation) { + // map logged type to its custom logger, eg + // { Point.class => CustomPointLogger.class } + var customLoggers = new HashMap(); + + var annotatedElements = roundEnv.getElementsAnnotatedWith(customLoggerAnnotation); + + var loggerSuperClass = + processingEnv + .getElementUtils() + .getTypeElement("edu.wpi.first.epilogue.logging.ClassSpecificLogger"); + + for (Element annotatedElement : annotatedElements) { + List targetTypes = List.of(); + for (AnnotationMirror annotationMirror : annotatedElement.getAnnotationMirrors()) { + for (var entry : annotationMirror.getElementValues().entrySet()) { + if ("value".equals(entry.getKey().getSimpleName().toString())) { + targetTypes = (List) entry.getValue().getValue(); + } + } + } + + boolean hasPublicNoArgConstructor = + annotatedElement.getEnclosedElements().stream() + .anyMatch( + enclosedElement -> + enclosedElement instanceof ExecutableElement exe + && exe.getKind() == ElementKind.CONSTRUCTOR + && exe.getModifiers().contains(Modifier.PUBLIC) + && exe.getParameters().isEmpty()); + + if (!hasPublicNoArgConstructor) { + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, + "Logger classes must have a public no-argument constructor", + annotatedElement); + continue; + } + + for (AnnotationValue value : targetTypes) { + var targetType = (DeclaredType) value.getValue(); + var reflectedTarget = targetType.asElement(); + + // eg ClassSpecificLogger + var requiredSuperClass = + processingEnv + .getTypeUtils() + .getDeclaredType( + loggerSuperClass, + processingEnv.getTypeUtils().getWildcardType(null, reflectedTarget.asType())); + + if (customLoggers.containsKey(targetType)) { + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, + "Multiple custom loggers detected for type " + targetType, + annotatedElement); + continue; + } + + if (!processingEnv + .getTypeUtils() + .isAssignable(annotatedElement.asType(), requiredSuperClass)) { + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, + "Not a subclass of ClassSpecificLogger<" + targetType + ">", + annotatedElement); + continue; + } + + customLoggers.put(targetType, (DeclaredType) annotatedElement.asType()); + } + } + + return customLoggers; + } + + private void processEpilogue(RoundEnvironment roundEnv, TypeElement epilogueAnnotation) { + var annotatedElements = roundEnv.getElementsAnnotatedWith(epilogueAnnotation); + + List loggerClassNames = new ArrayList<>(); + var mainRobotClasses = new ArrayList(); + + // Used to check for a main robot class + var robotBaseClass = + processingEnv.getElementUtils().getTypeElement("edu.wpi.first.wpilibj.TimedRobot").asType(); + + boolean validFields = validateFields(annotatedElements); + boolean validMethods = validateMethods(annotatedElements); + + if (!(validFields && validMethods)) { + // Generate nothing and bail + return; + } + + var classes = + annotatedElements.stream() + .filter(e -> e instanceof TypeElement) + .map(e -> (TypeElement) e) + .toList(); + for (TypeElement clazz : classes) { + try { + warnOfNonLoggableElements(clazz); + m_loggerGenerator.writeLoggerFile(clazz); + + if (processingEnv.getTypeUtils().isAssignable(clazz.getSuperclass(), robotBaseClass)) { + mainRobotClasses.add(clazz); + } + + loggerClassNames.add(StringUtils.loggerClassName(clazz)); + } catch (IOException e) { + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.ERROR, + "Could not write logger file for " + clazz.getQualifiedName(), + clazz); + e.printStackTrace(System.err); + } + } + + // Sort alphabetically + mainRobotClasses.sort(Comparator.comparing(c -> c.getSimpleName().toString())); + m_epiloguerGenerator.writeEpilogueFile(loggerClassNames, mainRobotClasses); + } + + private void warnOfNonLoggableElements(TypeElement clazz) { + var config = clazz.getAnnotation(Logged.class); + if (config.strategy() == Logged.Strategy.OPT_IN) { + // field and method validations will have already checked everything + return; + } + + for (Element element : clazz.getEnclosedElements()) { + if (element.getAnnotation(NotLogged.class) != null) { + // Explicitly opted out from, don't need to check + continue; + } + + if (element.getModifiers().contains(Modifier.STATIC)) { + // static elements are never logged + continue; + } + + if (element instanceof VariableElement v) { + // isNotLoggable will internally print a warning message + isNotLoggable(v, v.asType()); + } + + if (element instanceof ExecutableElement exe + && exe.getModifiers().contains(Modifier.PUBLIC) + && exe.getParameters().isEmpty()) { + // isNotLoggable will internally print a warning message + isNotLoggable(exe, exe.getReturnType()); + } + } + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ArrayHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ArrayHandler.java new file mode 100644 index 00000000000..dac0959bb23 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ArrayHandler.java @@ -0,0 +1,75 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.type.ArrayType; +import javax.lang.model.type.PrimitiveType; +import javax.lang.model.type.TypeMirror; + +/** + * Arrays of bytes, ints, flats, doubles, booleans, Strings, and struct-serializable objects can be + * logged. No other array types - including multidimensional arrays - are loggable. + */ +public class ArrayHandler extends ElementHandler { + private final StructHandler m_structHandler; + private final TypeMirror m_javaLangString; + + protected ArrayHandler(ProcessingEnvironment processingEnv) { + super(processingEnv); + + // use a struct handler for managing struct arrays + m_structHandler = new StructHandler(processingEnv); + + m_javaLangString = lookupTypeElement(processingEnv, "java.lang.String").asType(); + } + + @Override + public boolean isLoggable(Element element) { + return dataType(element) instanceof ArrayType arr + && isLoggableComponentType(arr.getComponentType()); + } + + /** + * Checks if an array containing elements of the given type can be logged. + * + * @param type the data type to check + * @return true if an array like {@code type[]} can be logged, false otherwise + */ + public boolean isLoggableComponentType(TypeMirror type) { + if (type instanceof PrimitiveType primitive) { + return switch (primitive.getKind()) { + case BYTE, INT, LONG, FLOAT, DOUBLE, BOOLEAN -> true; + default -> false; + }; + } + + return m_structHandler.isLoggableType(type) + || m_processingEnv.getTypeUtils().isAssignable(type, m_javaLangString); + } + + @Override + public String logInvocation(Element element) { + var dataType = dataType(element); + + // known to be an array type (assuming isLoggable is checked first); this is a safe cast + var componentType = ((ArrayType) dataType).getComponentType(); + + if (m_structHandler.isLoggableType(componentType)) { + // Struct arrays need to pass in the struct serializer + return "dataLogger.log(\"" + + loggedName(element) + + "\", " + + elementAccess(element) + + ", " + + m_structHandler.structAccess(componentType) + + ")"; + } else { + // Primitive or string array + return "dataLogger.log(\"" + loggedName(element) + "\", " + elementAccess(element) + ")"; + } + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/CollectionHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/CollectionHandler.java new file mode 100644 index 00000000000..27149a63fbd --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/CollectionHandler.java @@ -0,0 +1,57 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.type.DeclaredType; +import javax.lang.model.type.TypeMirror; + +/** + * Collections of strings and structs are loggable. Collections of boxed primitive types are not. + */ +public class CollectionHandler extends ElementHandler { + private final ArrayHandler m_arrayHandler; + private final TypeMirror m_collectionType; + private final StructHandler m_structHandler; + + protected CollectionHandler(ProcessingEnvironment processingEnv) { + super(processingEnv); + m_arrayHandler = new ArrayHandler(processingEnv); + m_collectionType = + processingEnv.getElementUtils().getTypeElement("java.util.Collection").asType(); + m_structHandler = new StructHandler(processingEnv); + } + + @Override + public boolean isLoggable(Element element) { + var dataType = dataType(element); + + return m_processingEnv + .getTypeUtils() + .isAssignable(dataType, m_processingEnv.getTypeUtils().erasure(m_collectionType)) + && dataType instanceof DeclaredType decl + && decl.getTypeArguments().size() == 1 + && m_arrayHandler.isLoggableComponentType(decl.getTypeArguments().get(0)); + } + + @Override + public String logInvocation(Element element) { + var dataType = dataType(element); + var componentType = ((DeclaredType) dataType).getTypeArguments().get(0); + + if (m_structHandler.isLoggableType(componentType)) { + return "dataLogger.log(\"" + + loggedName(element) + + "\", " + + elementAccess(element) + + ", " + + m_structHandler.structAccess(componentType) + + ")"; + } else { + return "dataLogger.log(\"" + loggedName(element) + "\", " + elementAccess(element) + ")"; + } + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ConfiguredLoggerHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ConfiguredLoggerHandler.java new file mode 100644 index 00000000000..a2226c6f2f1 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ConfiguredLoggerHandler.java @@ -0,0 +1,41 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import java.util.Map; +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.type.DeclaredType; +import javax.lang.model.type.TypeMirror; + +public class ConfiguredLoggerHandler extends ElementHandler { + private final Map m_customLoggers; + + protected ConfiguredLoggerHandler( + ProcessingEnvironment processingEnv, Map customLoggers) { + super(processingEnv); + + this.m_customLoggers = customLoggers; + } + + @Override + public boolean isLoggable(Element element) { + return m_customLoggers.containsKey(dataType(element)); + } + + @Override + public String logInvocation(Element element) { + var dataType = dataType(element); + var loggerType = m_customLoggers.get(dataType); + + return "Epilogue." + + StringUtils.lowerCamelCase(loggerType.asElement().getSimpleName()) + + ".tryUpdate(dataLogger.getSubLogger(\"" + + loggedName(element) + + "\"), " + + elementAccess(element) + + ", Epilogue.getConfig().errorHandler)"; + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ElementHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ElementHandler.java new file mode 100644 index 00000000000..1903f6a4b92 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/ElementHandler.java @@ -0,0 +1,136 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import edu.wpi.first.epilogue.Logged; +import edu.wpi.first.epilogue.logging.ClassSpecificLogger; +import edu.wpi.first.epilogue.logging.DataLogger; +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.element.ExecutableElement; +import javax.lang.model.element.Modifier; +import javax.lang.model.element.TypeElement; +import javax.lang.model.element.VariableElement; +import javax.lang.model.type.TypeMirror; + +/** + * Handles logging of fields or methods. An element that passes the {@link #isLoggable(Element)} + * check guarantees that {@link #logInvocation(Element)} will generate a code snippet that will log + * that element. Some subclasses may return {@code null} for the invocation to signal that the + * element should not be logged, but still be considered loggable for the purposes of error + * messaging during the compilation phase. + */ +public abstract class ElementHandler { + protected final ProcessingEnvironment m_processingEnv; + + /** + * Instantiates the handler. + * + * @param processingEnv the processing environment, used to look up type information + */ + protected ElementHandler(ProcessingEnvironment processingEnv) { + this.m_processingEnv = processingEnv; + } + + protected static TypeElement lookupTypeElement(ProcessingEnvironment processingEnv, String name) { + return processingEnv.getElementUtils().getTypeElement(name); + } + + /** + * Gets the type of data that would be logged by a field or method. + * + * @param element the field or method element to check + * @return the logged datatype + */ + protected TypeMirror dataType(Element element) { + if (element instanceof VariableElement field) { + return field.asType(); + } else if (element instanceof ExecutableElement method) { + return method.getReturnType(); + } else { + throw new IllegalStateException("Unexpected" + element.getClass().getName()); + } + } + + /** + * Gets the name of a field or method as it would appear in logs. + * + * @param element the field or method element to check + * @return the name specified in the {@link Logged @Logged} annotation on the element, if present; + * otherwise, the field or method's name with no modifications + */ + public String loggedName(Element element) { + var elementName = element.getSimpleName().toString(); + var config = element.getAnnotation(Logged.class); + + if (config != null && !config.name().isBlank()) { + return config.name(); + } else { + return elementName; + } + } + + /** + * Generates the code snippet to use to access a field or method on a logged object. Private + * fields are accessed via {@link java.lang.invoke.VarHandle VarHandles} and private methods are + * accessed via {@link java.lang.invoke.MethodHandle MethodHandles} (note that this requires the + * logger file to generate those fields). Because the generated logger files are in the same + * package as the logged type, package-private, protected, and public fields and methods are + * always accessible using normal field reads and method calls. Values returned by {@code + * VarHandle} and {@code MethodHandle} invocations will be cast to the appropriate data type. + * + * @param element the element to generate the access for + * @return the generated access snippet + */ + public String elementAccess(Element element) { + if (element instanceof VariableElement field) { + return fieldAccess(field); + } else if (element instanceof ExecutableElement method) { + return methodAccess(method); + } else { + throw new IllegalStateException("Unexpected" + element.getClass().getName()); + } + } + + private static String fieldAccess(VariableElement field) { + if (field.getModifiers().contains(Modifier.PRIVATE)) { + // (com.example.Foo) $fooField.get(object) + return "(" + field.asType() + ") $" + field.getSimpleName() + ".get(object)"; + } else { + // object.fooField + return "object." + field.getSimpleName(); + } + } + + private static String methodAccess(ExecutableElement method) { + if (method.getModifiers().contains(Modifier.PRIVATE)) { + // (com.example.Foo) _getFoo.invoke(object) + // NOTE: Currently, only public methods are logged, so this branch will not be used + return "(" + method.getReturnType() + ") _" + method.getSimpleName() + ".invoke(object)"; + } else { + // object.getFoo() + return "object." + method.getSimpleName() + "()"; + } + } + + /** + * Checks if a field or method can be logged by this handler. + * + * @param element the field or method element to check + * @return true if the element can be logged, false if not + */ + public abstract boolean isLoggable(Element element); + + /** + * Generates a code snippet to place in a generated logger file to log the value of a field or + * method. Log invocations are placed in a generated implementation of {@link + * ClassSpecificLogger#update(DataLogger, Object)}, with access to the data logger and logged + * object passed to the method call. + * + * @param element the field or method element to generate the logger call for + * @return the generated log invocation + */ + public abstract String logInvocation(Element element); +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EnumHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EnumHandler.java new file mode 100644 index 00000000000..56a0ad0bb65 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EnumHandler.java @@ -0,0 +1,33 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.type.TypeMirror; + +public class EnumHandler extends ElementHandler { + private final TypeMirror m_javaLangEnum; + + protected EnumHandler(ProcessingEnvironment processingEnv) { + super(processingEnv); + + // raw type java.lang.Enum + m_javaLangEnum = + processingEnv + .getTypeUtils() + .erasure(processingEnv.getElementUtils().getTypeElement("java.lang.Enum").asType()); + } + + @Override + public boolean isLoggable(Element element) { + return m_processingEnv.getTypeUtils().isAssignable(dataType(element), m_javaLangEnum); + } + + @Override + public String logInvocation(Element element) { + return "dataLogger.log(\"" + loggedName(element) + "\", " + elementAccess(element) + ")"; + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EpilogueGenerator.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EpilogueGenerator.java new file mode 100644 index 00000000000..54050026a67 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EpilogueGenerator.java @@ -0,0 +1,172 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import edu.wpi.first.epilogue.EpilogueConfiguration; +import java.io.IOException; +import java.io.PrintWriter; +import java.util.Collection; +import java.util.List; +import java.util.Map; +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.TypeElement; +import javax.lang.model.type.DeclaredType; +import javax.lang.model.type.TypeMirror; + +/** + * Generates the {@code Epilogue} file used as the main entry point to logging with Epilogue in a + * robot program. {@code Epilogue} has instances of every generated logger class, a {@link + * EpilogueConfiguration config} object, and (if the main robot class inherits from {@link + * edu.wpi.first.wpilibj.TimedRobot TimedRobot}) a {@code bind()} method to automatically add a + * periodic logging call to the robot. + */ +public class EpilogueGenerator { + private final ProcessingEnvironment m_processingEnv; + private final Map m_customLoggers; + + public EpilogueGenerator( + ProcessingEnvironment processingEnv, Map customLoggers) { + this.m_processingEnv = processingEnv; + this.m_customLoggers = customLoggers; + } + + /** + * Creates the Epilogue file, which is the main entry point for users to set up and interact with + * the generated loggers. + * + * @param loggerClassNames the names of the generated logger classes. Each of these will be + * instantiated in a public static field on the Epilogue class. + * @param mainRobotClasses the main robot classes. May be empty. Used to generate a {@code bind()} + * method to add a callback hook to a TimedRobot to log itself. + */ + @SuppressWarnings("checkstyle:LineLength") // Source code templates exceed the line length limit + public void writeEpilogueFile( + List loggerClassNames, Collection mainRobotClasses) { + try { + var centralStore = + m_processingEnv.getFiler().createSourceFile("edu.wpi.first.epilogue.Epilogue"); + + try (var out = new PrintWriter(centralStore.openOutputStream())) { + out.println("package edu.wpi.first.epilogue;"); + out.println(); + + loggerClassNames.stream() + .sorted() + .forEach( + name -> { + if (!name.contains(".")) { + // Logger is in the global namespace, don't need to import + return; + } + + out.println("import " + name + ";"); + }); + m_customLoggers.values().stream() + .distinct() + .forEach( + loggerType -> { + var name = loggerType.asElement().toString(); + if (!name.contains(".")) { + // Logger is in the global namespace, don't need to import + return; + } + out.println("import " + name + ";"); + }); + out.println(); + + out.println("public final class Epilogue {"); + out.println( + " private static final EpilogueConfiguration config = new EpilogueConfiguration();"); + out.println(); + + loggerClassNames.forEach( + name -> { + String simple = StringUtils.simpleName(name); + + // public static final FooLogger fooLogger = new FooLogger(); + out.print(" public static final "); + out.print(simple); + out.print(" "); + out.print(StringUtils.lowerCamelCase(simple)); + out.print(" = new "); + out.print(simple); + out.println("();"); + }); + m_customLoggers.values().stream() + .distinct() + .forEach( + loggerType -> { + var loggerTypeName = loggerType.asElement().getSimpleName(); + out.println( + " public static final " + + loggerTypeName + + " " + + StringUtils.lowerCamelCase(loggerTypeName) + + " = new " + + loggerTypeName + + "();"); + }); + out.println(); + + out.println( + """ + public static void configure(java.util.function.Consumer configurator) { + configurator.accept(config); + } + + public static EpilogueConfiguration getConfig() { + return config; + } + """); + + out.println( + """ + /** + * Checks if data associated with a given importance level should be logged. + */ + public static boolean shouldLog(Logged.Importance importance) { + return importance.compareTo(config.minimumImportance) >= 0; + } + """ + .stripTrailing()); + + // Only generate a binding if the robot class is a TimedRobot + if (!mainRobotClasses.isEmpty()) { + for (TypeElement mainRobotClass : mainRobotClasses) { + String robotClassName = mainRobotClass.getQualifiedName().toString(); + + out.println(); + out.print( + """ + /** + * Binds Epilogue updates to a timed robot's update period. Log calls will be made at the + * same update rate as the robot's loop function, but will be offset by a full phase + * (for example, a 20ms update rate but 10ms offset from the main loop invocation) to + * help avoid high CPU loads. However, this does mean that any logged data that reads + * directly from sensors will be slightly different from data used in the main robot + * loop. + */ + """); + out.println(" public static void bind(" + robotClassName + " robot) {"); + out.println(" robot.addPeriodic(() -> {"); + out.println(" long start = System.nanoTime();"); + out.println( + " " + + StringUtils.loggerFieldName(mainRobotClass) + + ".tryUpdate(config.dataLogger.getSubLogger(config.root), robot, config.errorHandler);"); + out.println( + " edu.wpi.first.networktables.NetworkTableInstance.getDefault().getEntry(\"Epilogue/Stats/Last Run\").setDouble((System.nanoTime() - start) / 1e6);"); + out.println(" }, robot.getPeriod(), robot.getPeriod() / 2);"); + out.println(" }"); + } + } + + out.println("}"); + } + } catch (IOException e) { + throw new RuntimeException(e); + } + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/LoggableHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/LoggableHandler.java new file mode 100644 index 00000000000..71367fc730f --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/LoggableHandler.java @@ -0,0 +1,43 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import edu.wpi.first.epilogue.Logged; +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.type.DeclaredType; +import javax.lang.model.type.TypeMirror; + +/** Handles logging for types annotated with the {@link Logged @Logged} annotation. */ +public class LoggableHandler extends ElementHandler { + protected LoggableHandler(ProcessingEnvironment processingEnv) { + super(processingEnv); + } + + @Override + public boolean isLoggable(Element element) { + var dataType = dataType(element); + return dataType.getAnnotation(Logged.class) != null + || dataType instanceof DeclaredType decl + && decl.asElement().getAnnotation(Logged.class) != null; + } + + @Override + public String logInvocation(Element element) { + TypeMirror dataType = dataType(element); + var reflectedType = + m_processingEnv + .getElementUtils() + .getTypeElement(m_processingEnv.getTypeUtils().erasure(dataType).toString()); + + return "Epilogue." + + StringUtils.loggerFieldName(reflectedType) + + ".tryUpdate(dataLogger.getSubLogger(\"" + + loggedName(element) + + "\"), " + + elementAccess(element) + + ", Epilogue.getConfig().errorHandler)"; + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/LoggerGenerator.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/LoggerGenerator.java new file mode 100644 index 00000000000..4c7392217b2 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/LoggerGenerator.java @@ -0,0 +1,245 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import static java.util.stream.Collectors.groupingBy; +import static java.util.stream.Collectors.toList; + +import edu.wpi.first.epilogue.Logged; +import edu.wpi.first.epilogue.NotLogged; +import java.io.IOException; +import java.io.PrintWriter; +import java.util.EnumMap; +import java.util.List; +import java.util.function.Predicate; +import java.util.stream.Stream; +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.element.ExecutableElement; +import javax.lang.model.element.Modifier; +import javax.lang.model.element.TypeElement; +import javax.lang.model.element.VariableElement; + +/** Generates logger class files for {@link Logged @Logged}-annotated classes. */ +public class LoggerGenerator { + private final ProcessingEnvironment m_processingEnv; + private final List m_handlers; + + public LoggerGenerator(ProcessingEnvironment processingEnv, List handlers) { + this.m_processingEnv = processingEnv; + this.m_handlers = handlers; + } + + private static boolean isNotSkipped(Element e) { + return e.getAnnotation(NotLogged.class) == null; + } + + /** + * Generates the logger class used to handle data objects of the given type. The generated logger + * class will subclass from {@link edu.wpi.first.epilogue.logging.ClassSpecificLogger} and + * implement the {@code update()} method to populate a data log with information from an instance + * of the data type. + * + * @param clazz the data type that the logger should support. + * @throws IOException if the file could not be written + */ + public void writeLoggerFile(TypeElement clazz) throws IOException { + var config = clazz.getAnnotation(Logged.class); + boolean requireExplicitOptIn = config.strategy() == Logged.Strategy.OPT_IN; + + Predicate notSkipped = LoggerGenerator::isNotSkipped; + Predicate optedIn = + e -> !requireExplicitOptIn || e.getAnnotation(Logged.class) != null; + + var fieldsToLog = + clazz.getEnclosedElements().stream() + .filter(e -> e instanceof VariableElement) + .map(e -> (VariableElement) e) + .filter(notSkipped) + .filter(optedIn) + .filter(e -> !e.getModifiers().contains(Modifier.STATIC)) + .filter(this::isLoggable) + .toList(); + + var methodsToLog = + clazz.getEnclosedElements().stream() + .filter(e -> e instanceof ExecutableElement) + .map(e -> (ExecutableElement) e) + .filter(notSkipped) + .filter(optedIn) + .filter(e -> !e.getModifiers().contains(Modifier.STATIC)) + .filter(e -> e.getModifiers().contains(Modifier.PUBLIC)) + .filter(e -> e.getParameters().isEmpty()) + .filter(e -> e.getReceiverType() != null) + .filter(this::isLoggable) + .toList(); + + writeLoggerFile(clazz.getQualifiedName().toString(), config, fieldsToLog, methodsToLog); + } + + private void writeLoggerFile( + String className, + Logged classConfig, + List loggableFields, + List loggableMethods) + throws IOException { + String packageName = null; + int lastDot = className.lastIndexOf('.'); + if (lastDot > 0) { + packageName = className.substring(0, lastDot); + } + + String simpleClassName = StringUtils.simpleName(className); + String loggerClassName = className + "Logger"; + String loggerSimpleClassName = loggerClassName.substring(lastDot + 1); + + // Use the name on the class config to set the generated logger names + // This helps to avoid naming conflicts + if (!classConfig.name().isBlank()) { + loggerSimpleClassName = + StringUtils.capitalize(classConfig.name().replaceAll(" ", "")) + "Logger"; + if (lastDot > 0) { + loggerClassName = packageName + "." + loggerSimpleClassName; + } else { + loggerClassName = loggerSimpleClassName; + } + } + + var loggerFile = m_processingEnv.getFiler().createSourceFile(loggerClassName); + + var privateFields = + loggableFields.stream().filter(e -> e.getModifiers().contains(Modifier.PRIVATE)).toList(); + boolean requiresVarHandles = !privateFields.isEmpty(); + + try (var out = new PrintWriter(loggerFile.openWriter())) { + if (packageName != null) { + // package com.example; + out.println("package " + packageName + ";"); + out.println(); + } + + out.println("import edu.wpi.first.epilogue.Logged;"); + out.println("import edu.wpi.first.epilogue.Epilogue;"); + out.println("import edu.wpi.first.epilogue.logging.ClassSpecificLogger;"); + out.println("import edu.wpi.first.epilogue.logging.DataLogger;"); + if (requiresVarHandles) { + out.println("import java.lang.invoke.MethodHandles;"); + out.println("import java.lang.invoke.VarHandle;"); + } + out.println(); + + // public class FooLogger implements ClassSpecificLogger { + out.println( + "public class " + + loggerSimpleClassName + + " extends ClassSpecificLogger<" + + simpleClassName + + "> {"); + + if (requiresVarHandles) { + for (var privateField : privateFields) { + // This field needs a VarHandle to access. + // Cache it in the class to avoid lookups + out.println(" private static final VarHandle $" + privateField.getSimpleName() + ";"); + } + out.println(); + + var clazz = simpleClassName + ".class"; + + out.println(" static {"); + out.println(" try {"); + out.println( + " var lookup = MethodHandles.privateLookupIn(" + + clazz + + ", MethodHandles.lookup());"); + + for (var privateField : privateFields) { + var fieldName = privateField.getSimpleName(); + out.println( + " $" + + fieldName + + " = lookup.findVarHandle(" + + clazz + + ", \"" + + fieldName + + "\", " + + m_processingEnv.getTypeUtils().erasure(privateField.asType()) + + ".class);"); + } + + out.println(" } catch (ReflectiveOperationException e) {"); + out.println( + " throw new RuntimeException(" + + "\"[EPILOGUE] Could not load private fields for logging!\", e);"); + out.println(" }"); + out.println(" }"); + out.println(); + } + + out.println(" public " + loggerSimpleClassName + "() {"); + out.println(" super(" + simpleClassName + ".class);"); + out.println(" }"); + out.println(); + + // @Override + // public void update(DataLogger dataLogger, Foo object) { + out.println(" @Override"); + out.println(" public void update(DataLogger dataLogger, " + simpleClassName + " object) {"); + + // Build a map of importance levels to the fields logged at those levels + // e.g. { DEBUG: [fieldA, fieldB], INFO: [fieldC], CRITICAL: [fieldD, fieldE, fieldF] } + var loggedElementsByImportance = + Stream.concat(loggableFields.stream(), loggableMethods.stream()) + .collect( + groupingBy( + element -> { + var config = element.getAnnotation(Logged.class); + if (config == null) { + // No configuration on this element, fall back to the class-level + // configuration + return classConfig.importance(); + } else { + return config.importance(); + } + }, + () -> + new EnumMap<>(Logged.Importance.class), // EnumMap for consistent ordering + toList())); + + loggedElementsByImportance.forEach( + (importance, elements) -> { + out.println( + " if (Epilogue.shouldLog(Logged.Importance." + importance.name() + ")) {"); + + for (var loggableElement : elements) { + // findFirst for prioritization + var handler = + m_handlers.stream().filter(h -> h.isLoggable(loggableElement)).findFirst(); + + handler.ifPresent( + h -> { + // May be null if the handler consumes the element but does not actually want it + // to be logged. For example, the sendable handler consumes all sendable types + // but does not log commands or subsystems, to prevent excessive warnings about + // unloggable commands. + var logInvocation = h.logInvocation(loggableElement); + if (logInvocation != null) { + out.println(logInvocation.indent(6).stripTrailing() + ";"); + } + }); + } + + out.println(" }"); + }); + + out.println(" }"); + out.println("}"); + } + } + + private boolean isLoggable(Element element) { + return m_handlers.stream().anyMatch(h -> h.isLoggable(element)); + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/MeasureHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/MeasureHandler.java new file mode 100644 index 00000000000..d34e73add76 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/MeasureHandler.java @@ -0,0 +1,37 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.type.TypeMirror; + +public class MeasureHandler extends ElementHandler { + private final TypeMirror m_measure; + + protected MeasureHandler(ProcessingEnvironment processingEnv) { + super(processingEnv); + + m_measure = + processingEnv + .getTypeUtils() + .erasure( + processingEnv + .getElementUtils() + .getTypeElement("edu.wpi.first.units.Measure") + .asType()); + } + + @Override + public boolean isLoggable(Element element) { + return m_processingEnv.getTypeUtils().isAssignable(dataType(element), m_measure); + } + + @Override + public String logInvocation(Element element) { + // DataLogger has builtin support for logging measures + return "dataLogger.log(\"" + loggedName(element) + "\", " + elementAccess(element) + ")"; + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/PrimitiveHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/PrimitiveHandler.java new file mode 100644 index 00000000000..f942f992485 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/PrimitiveHandler.java @@ -0,0 +1,41 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import static javax.lang.model.type.TypeKind.BOOLEAN; +import static javax.lang.model.type.TypeKind.BYTE; +import static javax.lang.model.type.TypeKind.CHAR; +import static javax.lang.model.type.TypeKind.DOUBLE; +import static javax.lang.model.type.TypeKind.FLOAT; +import static javax.lang.model.type.TypeKind.INT; +import static javax.lang.model.type.TypeKind.LONG; +import static javax.lang.model.type.TypeKind.SHORT; + +import java.util.Set; +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.type.TypeMirror; + +public class PrimitiveHandler extends ElementHandler { + private final TypeMirror m_javaLangString; + + protected PrimitiveHandler(ProcessingEnvironment processingEnv) { + super(processingEnv); + + m_javaLangString = processingEnv.getElementUtils().getTypeElement("java.lang.String").asType(); + } + + @Override + public boolean isLoggable(Element element) { + return m_processingEnv.getTypeUtils().isAssignable(dataType(element), m_javaLangString) + || Set.of(BYTE, CHAR, SHORT, INT, LONG, FLOAT, DOUBLE, BOOLEAN) + .contains(dataType(element).getKind()); + } + + @Override + public String logInvocation(Element element) { + return "dataLogger.log(\"" + loggedName(element) + "\", " + elementAccess(element) + ")"; + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/SendableHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/SendableHandler.java new file mode 100644 index 00000000000..e01e82017db --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/SendableHandler.java @@ -0,0 +1,56 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.type.TypeMirror; + +public class SendableHandler extends ElementHandler { + private final TypeMirror m_sendableType; + private final TypeMirror m_commandType; + private final TypeMirror m_subsystemType; + + protected SendableHandler(ProcessingEnvironment processingEnv) { + super(processingEnv); + + m_sendableType = + lookupTypeElement(processingEnv, "edu.wpi.first.util.sendable.Sendable").asType(); + m_commandType = + lookupTypeElement(processingEnv, "edu.wpi.first.wpilibj2.command.Command").asType(); + m_subsystemType = + lookupTypeElement(processingEnv, "edu.wpi.first.wpilibj2.command.SubsystemBase").asType(); + } + + @Override + public boolean isLoggable(Element element) { + var dataType = dataType(element); + + // Accept any sendable type. However, the log invocation will return null + // for sendable types that should not be logged (commands, subsystems) + return m_processingEnv.getTypeUtils().isAssignable(dataType, m_sendableType); + } + + @Override + public String logInvocation(Element element) { + var dataType = dataType(element); + + if (m_processingEnv.getTypeUtils().isAssignable(dataType, m_commandType) + || m_processingEnv.getTypeUtils().isAssignable(dataType, m_subsystemType)) { + // Do not log commands or subsystems via their sendable implementations + // We accept all sendable objects to prevent them from being reported as not loggable, + // but their sendable implementations do not include helpful information. + // Users are free to provide custom logging implementations for commands, and tag their + // subsystems with @Logged to log their contents automatically + return null; + } + + return "logSendable(dataLogger.getSubLogger(\"" + + loggedName(element) + + "\"), " + + elementAccess(element) + + ")"; + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/StringUtils.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/StringUtils.java new file mode 100644 index 00000000000..6cc43e53d7f --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/StringUtils.java @@ -0,0 +1,110 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import edu.wpi.first.epilogue.Logged; +import javax.lang.model.element.TypeElement; + +public final class StringUtils { + private StringUtils() { + throw new UnsupportedOperationException("This is a utility class!"); + } + + /** + * Gets the simple name of a fully qualified class. + * + * @param fqn the fully qualified class name + * @return the simple class name, without a package specifier + */ + public static String simpleName(String fqn) { + return fqn.substring(fqn.lastIndexOf('.') + 1); + } + + /** + * Capitalizes a string. The first character will be capitalized, and the rest of the string will + * be left as is. + * + * @param str the string to capitalize + * @return the capitalized string + */ + public static String capitalize(CharSequence str) { + return Character.toUpperCase(str.charAt(0)) + str.subSequence(1, str.length()).toString(); + } + + /** + * Converts a string to a lower camel-cased version. This requires the input string to only + * consist of alphanumeric characters, without underscores, spaces, or any other special + * character. + * + * @param str the string to convert + * @return the lower camel-case version of the string + */ + public static String lowerCamelCase(CharSequence str) { + StringBuilder builder = new StringBuilder(str.length()); + + int i = 0; + for (; + i < str.length() + && (i == 0 + || i == str.length() - 1 + || Character.isUpperCase(str.charAt(i)) + && Character.isUpperCase(str.charAt(i + 1))); + i++) { + builder.append(Character.toLowerCase(str.charAt(i))); + } + + builder.append(str.subSequence(i, str.length())); + return builder.toString(); + } + + /** + * Gets the name of the field used to hold a logger for data of the given type. + * + * @param clazz the data type that the logger supports + * @return the logger field name + */ + public static String loggerFieldName(TypeElement clazz) { + return lowerCamelCase(simpleName(loggerClassName(clazz))); + } + + /** + * Gets the name of the generated class used to log data of the given type. This will be + * fully-qualified class name, such as {@code "frc.robot.MyRobotLogger"}. + * + * @param clazz the data type that the logger supports + * @return the logger class name + */ + public static String loggerClassName(TypeElement clazz) { + var config = clazz.getAnnotation(Logged.class); + var className = clazz.getQualifiedName().toString(); + + String packageName; + int lastDot = className.lastIndexOf('.'); + if (lastDot <= 0) { + packageName = null; + } else { + packageName = className.substring(0, lastDot); + } + + String loggerClassName; + + // Use the name on the class config to set the generated logger names + // This helps to avoid naming conflicts + if (config.name().isBlank()) { + loggerClassName = className + "Logger"; + } else { + String cleaned = config.name().replaceAll(" ", ""); + + var loggerSimpleClassName = StringUtils.capitalize(cleaned) + "Logger"; + if (packageName != null) { + loggerClassName = packageName + "." + loggerSimpleClassName; + } else { + loggerClassName = loggerSimpleClassName; + } + } + + return loggerClassName; + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/StructHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/StructHandler.java new file mode 100644 index 00000000000..ead545cc072 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/StructHandler.java @@ -0,0 +1,50 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.type.TypeMirror; +import javax.lang.model.util.Types; + +public class StructHandler extends ElementHandler { + private final TypeMirror m_serializable; + private final Types m_typeUtils; + + protected StructHandler(ProcessingEnvironment processingEnv) { + super(processingEnv); + m_serializable = + processingEnv + .getElementUtils() + .getTypeElement("edu.wpi.first.util.struct.StructSerializable") + .asType(); + m_typeUtils = processingEnv.getTypeUtils(); + } + + @Override + public boolean isLoggable(Element element) { + return m_typeUtils.isAssignable(dataType(element), m_serializable); + } + + public boolean isLoggableType(TypeMirror type) { + return m_typeUtils.isAssignable(type, m_serializable); + } + + public String structAccess(TypeMirror serializableType) { + var className = m_typeUtils.erasure(serializableType).toString(); + return className + ".struct"; + } + + @Override + public String logInvocation(Element element) { + return "dataLogger.log(\"" + + loggedName(element) + + "\", " + + elementAccess(element) + + ", " + + structAccess(dataType(element)) + + ")"; + } +} diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/SupplierHandler.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/SupplierHandler.java new file mode 100644 index 00000000000..70e31543842 --- /dev/null +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/SupplierHandler.java @@ -0,0 +1,67 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import javax.annotation.processing.ProcessingEnvironment; +import javax.lang.model.element.Element; +import javax.lang.model.type.TypeMirror; + +public class SupplierHandler extends ElementHandler { + private final TypeMirror m_booleanSupplier; + private final TypeMirror m_intSupplier; + private final TypeMirror m_longSupplier; + private final TypeMirror m_doubleSupplier; + + protected SupplierHandler(ProcessingEnvironment processingEnv) { + super(processingEnv); + + m_booleanSupplier = + processingEnv + .getElementUtils() + .getTypeElement("java.util.function.BooleanSupplier") + .asType(); + m_intSupplier = + processingEnv.getElementUtils().getTypeElement("java.util.function.IntSupplier").asType(); + m_longSupplier = + processingEnv.getElementUtils().getTypeElement("java.util.function.LongSupplier").asType(); + m_doubleSupplier = + processingEnv + .getElementUtils() + .getTypeElement("java.util.function.DoubleSupplier") + .asType(); + } + + @Override + public boolean isLoggable(Element element) { + return m_processingEnv.getTypeUtils().isAssignable(dataType(element), m_booleanSupplier) + || m_processingEnv.getTypeUtils().isAssignable(dataType(element), m_intSupplier) + || m_processingEnv.getTypeUtils().isAssignable(dataType(element), m_longSupplier) + || m_processingEnv.getTypeUtils().isAssignable(dataType(element), m_doubleSupplier); + } + + @Override + public String logInvocation(Element element) { + return "dataLogger.log(\"" + loggedName(element) + "\", " + elementAccess(element) + ")"; + } + + @Override + public String elementAccess(Element element) { + var typeUtils = m_processingEnv.getTypeUtils(); + var dataType = dataType(element); + String base = super.elementAccess(element); + + if (typeUtils.isAssignable(dataType, m_booleanSupplier)) { + return base + ".getAsBoolean()"; + } else if (typeUtils.isAssignable(dataType, m_intSupplier)) { + return base + ".getAsInt()"; + } else if (typeUtils.isAssignable(dataType, m_longSupplier)) { + return base + ".getAsLong()"; + } else if (typeUtils.isAssignable(dataType, m_doubleSupplier)) { + return base + ".getAsDouble()"; + } else { + throw new IllegalArgumentException("Element type is unsupported: " + dataType); + } + } +} diff --git a/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/AnnotationProcessorTest.java b/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/AnnotationProcessorTest.java new file mode 100644 index 00000000000..7304e731a66 --- /dev/null +++ b/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/AnnotationProcessorTest.java @@ -0,0 +1,1172 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import static com.google.testing.compile.CompilationSubject.assertThat; +import static com.google.testing.compile.Compiler.javac; +import static org.junit.jupiter.api.Assertions.assertAll; +import static org.junit.jupiter.api.Assertions.assertEquals; + +import com.google.testing.compile.Compilation; +import com.google.testing.compile.JavaFileObjects; +import java.io.IOException; +import java.util.List; +import java.util.Locale; +import javax.tools.Diagnostic; +import javax.tools.JavaFileObject; +import org.junit.jupiter.api.Test; + +@SuppressWarnings("checkstyle:LineLength") // Source code templates exceed the line length limit +class AnnotationProcessorTest { + @Test + void simple() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + double x; + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void multiple() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + double x; + double y; + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + dataLogger.log("y", object.y); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void privateFields() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + private double x; + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + import java.lang.invoke.MethodHandles; + import java.lang.invoke.VarHandle; + + public class ExampleLogger extends ClassSpecificLogger { + private static final VarHandle $x; + + static { + try { + var lookup = MethodHandles.privateLookupIn(Example.class, MethodHandles.lookup()); + $x = lookup.findVarHandle(Example.class, "x", double.class); + } catch (ReflectiveOperationException e) { + throw new RuntimeException("[EPILOGUE] Could not load private fields for logging!", e); + } + } + + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", (double) $x.get(object)); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void privateWithGenerics() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + private edu.wpi.first.wpilibj.smartdashboard.SendableChooser chooser; + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + import java.lang.invoke.MethodHandles; + import java.lang.invoke.VarHandle; + + public class ExampleLogger extends ClassSpecificLogger { + private static final VarHandle $chooser; + + static { + try { + var lookup = MethodHandles.privateLookupIn(Example.class, MethodHandles.lookup()); + $chooser = lookup.findVarHandle(Example.class, "chooser", edu.wpi.first.wpilibj.smartdashboard.SendableChooser.class); + } catch (ReflectiveOperationException e) { + throw new RuntimeException("[EPILOGUE] Could not load private fields for logging!", e); + } + } + + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + logSendable(dataLogger.getSubLogger("chooser"), (edu.wpi.first.wpilibj.smartdashboard.SendableChooser) $chooser.get(object)); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void importanceLevels() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged(importance = Logged.Importance.INFO) + class Example { + @Logged(importance = Logged.Importance.DEBUG) double low; + @Logged(importance = Logged.Importance.INFO) int medium; + @Logged(importance = Logged.Importance.CRITICAL) long high; + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("low", object.low); + } + if (Epilogue.shouldLog(Logged.Importance.INFO)) { + dataLogger.log("medium", object.medium); + } + if (Epilogue.shouldLog(Logged.Importance.CRITICAL)) { + dataLogger.log("high", object.high); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void logEnum() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + enum E { + a, b, c; + } + E enumValue; // Should be logged + E[] enumArray; // Should not be logged + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("enumValue", object.enumValue); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void bytes() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + byte x; // Should be logged + byte[] arr1; // Should be logged + byte[][] arr2; // Should not be logged + + public byte getX() { return x; } + public byte[] getArr1() { return arr1; } + public byte[][] getArr2() { return arr2; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + dataLogger.log("arr1", object.arr1); + dataLogger.log("getX", object.getX()); + dataLogger.log("getArr1", object.getArr1()); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void chars() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + char x; // Should be logged + char[] arr1; // Should not be logged + char[][] arr2; // Should not be logged + + public char getX() { return x; } + public char[] getArr1() { return arr1; } + public char[][] getArr2() { return arr2; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + dataLogger.log("getX", object.getX()); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void shorts() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + short x; // Should be logged + short[] arr1; // Should not be logged + short[][] arr2; // Should not be logged + + public short getX() { return x; } + public short[] getArr1() { return arr1; } + public short[][] getArr2() { return arr2; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + dataLogger.log("getX", object.getX()); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void ints() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + int x; // Should be logged + int[] arr1; // Should be logged + int[][] arr2; // Should not be logged + + public int getX() { return x; } + public int[] getArr1() { return arr1; } + public int[][] getArr2() { return arr2; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + dataLogger.log("arr1", object.arr1); + dataLogger.log("getX", object.getX()); + dataLogger.log("getArr1", object.getArr1()); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void longs() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + long x; // Should be logged + long[] arr1; // Should be logged + long[][] arr2; // Should not be logged + + public long getX() { return x; } + public long[] getArr1() { return arr1; } + public long[][] getArr2() { return arr2; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + dataLogger.log("arr1", object.arr1); + dataLogger.log("getX", object.getX()); + dataLogger.log("getArr1", object.getArr1()); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void floats() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + float x; // Should be logged + float[] arr1; // Should be logged + float[][] arr2; // Should not be logged + + public float getX() { return x; } + public float[] getArr1() { return arr1; } + public float[][] getArr2() { return arr2; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + dataLogger.log("arr1", object.arr1); + dataLogger.log("getX", object.getX()); + dataLogger.log("getArr1", object.getArr1()); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void doubles() { + String source = + """ + package edu.wpi.first.epilogue; + + import java.util.List; + + @Logged + class Example { + double x; // Should be logged + double[] arr1; // Should be logged + double[][] arr2; // Should not be logged + List list; // Should not be logged + + public double getX() { return x; } + public double[] getArr1() { return arr1; } + public double[][] getArr2() { return arr2; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + dataLogger.log("arr1", object.arr1); + dataLogger.log("getX", object.getX()); + dataLogger.log("getArr1", object.getArr1()); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void booleans() { + String source = + """ + package edu.wpi.first.epilogue; + import java.util.List; + + @Logged + class Example { + boolean x; // Should be logged + boolean[] arr1; // Should be logged + boolean[][] arr2; // Should not be logged + List list; // Should not be logged + + public boolean getX() { return x; } + public boolean[] getArr1() { return arr1; } + public boolean[][] getArr2() { return arr2; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + dataLogger.log("arr1", object.arr1); + dataLogger.log("getX", object.getX()); + dataLogger.log("getArr1", object.getArr1()); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void strings() { + String source = + """ + package edu.wpi.first.epilogue; + + import java.util.List; + + @Logged + class Example { + String x; // Should be logged + String[] arr1; // Should be logged + String[][] arr2; // Should not be logged + List list; // Should be logged + + public String getX() { return x; } + public String[] getArr1() { return arr1; } + public String[][] getArr2() { return arr2; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x); + dataLogger.log("arr1", object.arr1); + dataLogger.log("list", object.list); + dataLogger.log("getX", object.getX()); + dataLogger.log("getArr1", object.getArr1()); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void structs() { + String source = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.util.struct.Struct; + import edu.wpi.first.util.struct.StructSerializable; + import java.util.List; + + @Logged + class Example { + static class Structable implements StructSerializable { + int x, y; + + public static final Struct struct = null; // value doesn't matter + } + + Structable x; // Should be logged + Structable[] arr1; // Should be logged + Structable[][] arr2; // Should not be logged + List list; // Should be logged + + public Structable getX() { return x; } + public Structable[] getArr1() { return arr1; } + public Structable[][] getArr2() { return arr2; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("x", object.x, edu.wpi.first.epilogue.Example.Structable.struct); + dataLogger.log("arr1", object.arr1, edu.wpi.first.epilogue.Example.Structable.struct); + dataLogger.log("list", object.list, edu.wpi.first.epilogue.Example.Structable.struct); + dataLogger.log("getX", object.getX(), edu.wpi.first.epilogue.Example.Structable.struct); + dataLogger.log("getArr1", object.getArr1(), edu.wpi.first.epilogue.Example.Structable.struct); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void lists() { + String source = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.util.struct.Struct; + import edu.wpi.first.util.struct.StructSerializable; + import java.util.*; + + @Logged + class Example { + /* Logged */ List list; + /* Not Logged */ List> nestedList; + /* Not logged */ List rawList; + /* Logged */ Set set; + /* Logged */ Queue queue; + /* Logged */ Stack stack; + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("list", object.list); + dataLogger.log("set", object.set); + dataLogger.log("queue", object.queue); + dataLogger.log("stack", object.stack); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void boxedPrimitiveLists() { + // Boxed primitives are not directly supported, nor are arrays of boxed primitives + // int[] is fine, but Integer[] is not + + String source = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.util.struct.Struct; + import edu.wpi.first.util.struct.StructSerializable; + import java.util.List; + + @Logged + class Example { + /* Not logged */ List ints; + /* Not logged */ List doubles; + /* Not logged */ List longs; + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void badLogSetup() { + String source = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.util.struct.Struct; + import edu.wpi.first.util.struct.StructSerializable; + import java.util.*; + + @Logged + class Example { + @Logged Map notLoggableType; + @Logged List rawType; + @NotLogged List skippedUnloggable; + + @Logged + private String privateMethod() { return ""; } + + @Logged + String packagePrivateMethod() { return ""; } + + @Logged + protected String protectedMethod() { return ""; } + + @Logged + public static String publicStaticMethod() { return ""; } + + @Logged + private static String privateStaticMethod() { return ""; } + + @Logged + public void publicVoidMethod() {} + + @Logged + public Map publicNonLoggableMethod() { return notLoggableType; } + } + """; + + Compilation compilation = + javac() + .withProcessors(new AnnotationProcessor()) + .compile(JavaFileObjects.forSourceString("edu.wpi.first.epilogue.Example", source)); + + assertThat(compilation).failed(); + assertThat(compilation).hadErrorCount(10); + + List> errors = compilation.errors(); + assertAll( + () -> + assertCompilationError( + "[EPILOGUE] You have opted in to logging on this field, but it is not a loggable data type!", + 9, + 31, + errors.get(0)), + () -> + assertCompilationError( + "[EPILOGUE] You have opted in to logging on this field, but it is not a loggable data type!", + 10, + 16, + errors.get(1)), + () -> + assertCompilationError( + "[EPILOGUE] Logged methods must be public", 14, 18, errors.get(2)), + () -> + assertCompilationError( + "[EPILOGUE] Logged methods must be public", 17, 10, errors.get(3)), + () -> + assertCompilationError( + "[EPILOGUE] Logged methods must be public", 20, 20, errors.get(4)), + () -> + assertCompilationError( + "[EPILOGUE] Logged methods cannot be static", 23, 24, errors.get(5)), + () -> + assertCompilationError( + "[EPILOGUE] Logged methods must be public", 26, 25, errors.get(6)), + () -> + assertCompilationError( + "[EPILOGUE] Logged methods cannot be static", 26, 25, errors.get(7)), + () -> + assertCompilationError( + "[EPILOGUE] You have opted in to logging on this method, but it does not return a loggable data type!", + 29, + 15, + errors.get(8)), + () -> + assertCompilationError( + "[EPILOGUE] You have opted in to logging on this method, but it does not return a loggable data type!", + 32, + 30, + errors.get(9))); + } + + @Test + void onGenericType() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + T value; + + public S upcast() { return (S) value; } + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + dataLogger.log("value", object.value); + dataLogger.log("upcast", object.upcast()); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void annotationInheritance() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Child {} + + class GoldenChild extends Child {} // inherits the @Logged annotation from the parent + + @Logged + interface IO {} + + class IOImpl implements IO {} + + @Logged + public class Example { + /* Logged */ Child child; + /* Not Logged */ GoldenChild goldenChild; + /* Logged */ IO io; + /* Not logged */ IOImpl ioImpl; + } + """; + + String expectedRootLogger = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + Epilogue.childLogger.tryUpdate(dataLogger.getSubLogger("child"), object.child, Epilogue.getConfig().errorHandler); + Epilogue.ioLogger.tryUpdate(dataLogger.getSubLogger("io"), object.io, Epilogue.getConfig().errorHandler); + } + } + } + """; + + assertLoggerGenerates(source, expectedRootLogger); + } + + @Test + void customLogger() { + String source = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.logging.*; + + record Point(int x, int y) {} + + @CustomLoggerFor(Point.class) + class CustomPointLogger extends ClassSpecificLogger { + public CustomPointLogger() { + super(Point.class); + } + + @Override + public void update(DataLogger dataLogger, Point point) { + // Implementation is irrelevant + } + } + + @Logged + class Example { + Point point; + } + """; + + String expectedGeneratedSource = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.Logged; + import edu.wpi.first.epilogue.Epilogue; + import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + import edu.wpi.first.epilogue.logging.DataLogger; + + public class ExampleLogger extends ClassSpecificLogger { + public ExampleLogger() { + super(Example.class); + } + + @Override + public void update(DataLogger dataLogger, Example object) { + if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { + Epilogue.customPointLogger.tryUpdate(dataLogger.getSubLogger("point"), object.point, Epilogue.getConfig().errorHandler); + } + } + } + """; + + assertLoggerGenerates(source, expectedGeneratedSource); + } + + @Test + void warnsAboutNonLoggableFields() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + Throwable t; + } + """; + + Compilation compilation = + javac() + .withProcessors(new AnnotationProcessor()) + .compile(JavaFileObjects.forSourceString("edu.wpi.first.epilogue.Example", source)); + + assertThat(compilation).succeeded(); + assertEquals(1, compilation.notes().size()); + var warning = compilation.notes().get(0); + var message = warning.getMessage(Locale.getDefault()); + assertEquals( + "[EPILOGUE] Excluded from logs because java.lang.Throwable is not a loggable data type", + message); + } + + private void assertCompilationError( + String message, long lineNumber, long col, Diagnostic diagnostic) { + assertAll( + () -> assertEquals(Diagnostic.Kind.ERROR, diagnostic.getKind(), "not an error"), + () -> + assertEquals( + message, diagnostic.getMessage(Locale.getDefault()), "error message mismatch"), + () -> assertEquals(lineNumber, diagnostic.getLineNumber(), "line number mismatch"), + () -> assertEquals(col, diagnostic.getColumnNumber(), "column number mismatch")); + } + + private void assertLoggerGenerates(String loggedClassContent, String loggerClassContent) { + Compilation compilation = + javac() + .withProcessors(new AnnotationProcessor()) + .compile( + JavaFileObjects.forSourceString( + "edu.wpi.first.epilogue.Example", loggedClassContent)); + + assertThat(compilation).succeeded(); + var generatedFiles = compilation.generatedSourceFiles(); + var generatedFile = + generatedFiles.stream() + .filter(jfo -> jfo.getName().contains("Example")) + .findFirst() + .orElseThrow(() -> new IllegalStateException("Logger file was not generated!")); + try { + var content = generatedFile.getCharContent(false); + assertEquals( + loggerClassContent.replace("\r\n", "\n"), content.toString().replace("\r\n", "\n")); + } catch (IOException e) { + throw new RuntimeException(e); + } + } +} diff --git a/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/EpilogueGeneratorTest.java b/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/EpilogueGeneratorTest.java new file mode 100644 index 00000000000..bf1c94049ef --- /dev/null +++ b/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/EpilogueGeneratorTest.java @@ -0,0 +1,326 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import static com.google.testing.compile.CompilationSubject.assertThat; +import static com.google.testing.compile.Compiler.javac; +import static org.junit.jupiter.api.Assertions.assertEquals; + +import com.google.testing.compile.Compilation; +import com.google.testing.compile.JavaFileObjects; +import java.io.IOException; +import org.junit.jupiter.api.Test; + +@SuppressWarnings("checkstyle:LineLength") // Source code templates exceed the line length limit +class EpilogueGeneratorTest { + @Test + void noFields() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example { + } + """; + + String expected = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.ExampleLogger; + + public final class Epilogue { + private static final EpilogueConfiguration config = new EpilogueConfiguration(); + + public static final ExampleLogger exampleLogger = new ExampleLogger(); + + public static void configure(java.util.function.Consumer configurator) { + configurator.accept(config); + } + + public static EpilogueConfiguration getConfig() { + return config; + } + + /** + * Checks if data associated with a given importance level should be logged. + */ + public static boolean shouldLog(Logged.Importance importance) { + return importance.compareTo(config.minimumImportance) >= 0; + } + } + """; + + assertGeneratedEpilogueContents(source, expected); + } + + /** Subclassing RobotBase should not generate the bind() method because it lacks addPeriodic(). */ + @Test + void robotBase() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example extends edu.wpi.first.wpilibj.RobotBase { + @Override + public void startCompetition() {} + @Override + public void endCompetition() {} + } + """; + + String expected = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.ExampleLogger; + + public final class Epilogue { + private static final EpilogueConfiguration config = new EpilogueConfiguration(); + + public static final ExampleLogger exampleLogger = new ExampleLogger(); + + public static void configure(java.util.function.Consumer configurator) { + configurator.accept(config); + } + + public static EpilogueConfiguration getConfig() { + return config; + } + + /** + * Checks if data associated with a given importance level should be logged. + */ + public static boolean shouldLog(Logged.Importance importance) { + return importance.compareTo(config.minimumImportance) >= 0; + } + } + """; + + assertGeneratedEpilogueContents(source, expected); + } + + @Test + void timedRobot() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class Example extends edu.wpi.first.wpilibj.TimedRobot { + } + """; + + String expected = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.ExampleLogger; + + public final class Epilogue { + private static final EpilogueConfiguration config = new EpilogueConfiguration(); + + public static final ExampleLogger exampleLogger = new ExampleLogger(); + + public static void configure(java.util.function.Consumer configurator) { + configurator.accept(config); + } + + public static EpilogueConfiguration getConfig() { + return config; + } + + /** + * Checks if data associated with a given importance level should be logged. + */ + public static boolean shouldLog(Logged.Importance importance) { + return importance.compareTo(config.minimumImportance) >= 0; + } + + /** + * Binds Epilogue updates to a timed robot's update period. Log calls will be made at the + * same update rate as the robot's loop function, but will be offset by a full phase + * (for example, a 20ms update rate but 10ms offset from the main loop invocation) to + * help avoid high CPU loads. However, this does mean that any logged data that reads + * directly from sensors will be slightly different from data used in the main robot + * loop. + */ + public static void bind(edu.wpi.first.epilogue.Example robot) { + robot.addPeriodic(() -> { + long start = System.nanoTime(); + exampleLogger.tryUpdate(config.dataLogger.getSubLogger(config.root), robot, config.errorHandler); + edu.wpi.first.networktables.NetworkTableInstance.getDefault().getEntry("Epilogue/Stats/Last Run").setDouble((System.nanoTime() - start) / 1e6); + }, robot.getPeriod(), robot.getPeriod() / 2); + } + } + """; + + assertGeneratedEpilogueContents(source, expected); + } + + @Test + void multipleRobots() { + String source = + """ + package edu.wpi.first.epilogue; + + @Logged + class AlphaBot extends edu.wpi.first.wpilibj.TimedRobot { } + + @Logged + class BetaBot extends edu.wpi.first.wpilibj.TimedRobot { } + """; + + String expected = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.AlphaBotLogger; + import edu.wpi.first.epilogue.BetaBotLogger; + + public final class Epilogue { + private static final EpilogueConfiguration config = new EpilogueConfiguration(); + + public static final AlphaBotLogger alphaBotLogger = new AlphaBotLogger(); + public static final BetaBotLogger betaBotLogger = new BetaBotLogger(); + + public static void configure(java.util.function.Consumer configurator) { + configurator.accept(config); + } + + public static EpilogueConfiguration getConfig() { + return config; + } + + /** + * Checks if data associated with a given importance level should be logged. + */ + public static boolean shouldLog(Logged.Importance importance) { + return importance.compareTo(config.minimumImportance) >= 0; + } + + /** + * Binds Epilogue updates to a timed robot's update period. Log calls will be made at the + * same update rate as the robot's loop function, but will be offset by a full phase + * (for example, a 20ms update rate but 10ms offset from the main loop invocation) to + * help avoid high CPU loads. However, this does mean that any logged data that reads + * directly from sensors will be slightly different from data used in the main robot + * loop. + */ + public static void bind(edu.wpi.first.epilogue.AlphaBot robot) { + robot.addPeriodic(() -> { + long start = System.nanoTime(); + alphaBotLogger.tryUpdate(config.dataLogger.getSubLogger(config.root), robot, config.errorHandler); + edu.wpi.first.networktables.NetworkTableInstance.getDefault().getEntry("Epilogue/Stats/Last Run").setDouble((System.nanoTime() - start) / 1e6); + }, robot.getPeriod(), robot.getPeriod() / 2); + } + + /** + * Binds Epilogue updates to a timed robot's update period. Log calls will be made at the + * same update rate as the robot's loop function, but will be offset by a full phase + * (for example, a 20ms update rate but 10ms offset from the main loop invocation) to + * help avoid high CPU loads. However, this does mean that any logged data that reads + * directly from sensors will be slightly different from data used in the main robot + * loop. + */ + public static void bind(edu.wpi.first.epilogue.BetaBot robot) { + robot.addPeriodic(() -> { + long start = System.nanoTime(); + betaBotLogger.tryUpdate(config.dataLogger.getSubLogger(config.root), robot, config.errorHandler); + edu.wpi.first.networktables.NetworkTableInstance.getDefault().getEntry("Epilogue/Stats/Last Run").setDouble((System.nanoTime() - start) / 1e6); + }, robot.getPeriod(), robot.getPeriod() / 2); + } + } + """; + + assertGeneratedEpilogueContents(source, expected); + } + + @Test + void genericCustomLogger() { + String source = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.logging.*; + + class A {} + class B extends A {} + class C extends A {} + + @CustomLoggerFor({A.class, B.class, C.class}) + class CustomLogger extends ClassSpecificLogger { + public CustomLogger() { super(A.class); } + + @Override + public void update(DataLogger logger, A object) {} // implementation is irrelevant + } + + @Logged + class Example { + A a_b_or_c; + B b; + C c; + } + """; + + String expected = + """ + package edu.wpi.first.epilogue; + + import edu.wpi.first.epilogue.ExampleLogger; + import edu.wpi.first.epilogue.CustomLogger; + + public final class Epilogue { + private static final EpilogueConfiguration config = new EpilogueConfiguration(); + + public static final ExampleLogger exampleLogger = new ExampleLogger(); + public static final CustomLogger customLogger = new CustomLogger(); + + public static void configure(java.util.function.Consumer configurator) { + configurator.accept(config); + } + + public static EpilogueConfiguration getConfig() { + return config; + } + + /** + * Checks if data associated with a given importance level should be logged. + */ + public static boolean shouldLog(Logged.Importance importance) { + return importance.compareTo(config.minimumImportance) >= 0; + } + } + """; + + assertGeneratedEpilogueContents(source, expected); + } + + private void assertGeneratedEpilogueContents( + String loggedClassContent, String loggerClassContent) { + Compilation compilation = + javac() + .withProcessors(new AnnotationProcessor()) + .compile(JavaFileObjects.forSourceString("", loggedClassContent)); + + assertThat(compilation).succeededWithoutWarnings(); + var generatedFiles = compilation.generatedSourceFiles(); + var generatedFile = + generatedFiles.stream() + .filter(jfo -> jfo.getName().contains("Epilogue")) + .findFirst() + .orElseThrow(() -> new IllegalStateException("Epilogue file was not generated!")); + try { + var content = generatedFile.getCharContent(false); + assertEquals( + loggerClassContent.replace("\r\n", "\n"), content.toString().replace("\r\n", "\n")); + } catch (IOException e) { + throw new RuntimeException(e); + } + } +} diff --git a/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/StringUtilsTest.java b/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/StringUtilsTest.java new file mode 100644 index 00000000000..4032260fff2 --- /dev/null +++ b/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/StringUtilsTest.java @@ -0,0 +1,19 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.processor; + +import static org.junit.jupiter.api.Assertions.assertEquals; + +import org.junit.jupiter.api.Test; + +class StringUtilsTest { + @Test + void lowerCamelCase() { + assertEquals("ioLogger", StringUtils.lowerCamelCase("IOLogger")); + assertEquals("ledSubsystem", StringUtils.lowerCamelCase("LEDSubsystem")); + assertEquals("fooBar", StringUtils.lowerCamelCase("FooBar")); + assertEquals("allcaps", StringUtils.lowerCamelCase("ALLCAPS")); + } +} diff --git a/epilogue-runtime/build.gradle b/epilogue-runtime/build.gradle new file mode 100644 index 00000000000..fb96095a0a5 --- /dev/null +++ b/epilogue-runtime/build.gradle @@ -0,0 +1,16 @@ +ext { + useJava = true + useCpp = false + baseId = 'epilogue-runtime' + groupId = 'edu.wpi.first.epilogue' + + devMain = '' +} + +apply from: "${rootDir}/shared/java/javacommon.gradle" + +dependencies { + api(project(':ntcore')) + api(project(':wpiutil')) + api(project(':wpiunits')) +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/CustomLoggerFor.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/CustomLoggerFor.java new file mode 100644 index 00000000000..93b11cf1f45 --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/CustomLoggerFor.java @@ -0,0 +1,30 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue; + +import java.lang.annotation.ElementType; +import java.lang.annotation.Retention; +import java.lang.annotation.RetentionPolicy; +import java.lang.annotation.Target; + +/** + * Placed on a subclass of {@code ClassSpecificLogger}. Epilogue will detect it at compile time and + * allow logging of data types compatible with the logger. + * + *

+ *   {@literal @}CustomLoggerFor(VendorMotorType.class)
+ *    class ExampleMotorLogger extends ClassSpecificLogger<VendorMotorType> { }
+ * 
+ */ +@Retention(RetentionPolicy.RUNTIME) +@Target(ElementType.TYPE) +public @interface CustomLoggerFor { + /** + * The class or classes of objects able to be logged with the annotated logger. + * + * @return the supported data types + */ + Class[] value(); +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java new file mode 100644 index 00000000000..e5b569bf0ae --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java @@ -0,0 +1,43 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue; + +import edu.wpi.first.epilogue.logging.DataLogger; +import edu.wpi.first.epilogue.logging.NTDataLogger; +import edu.wpi.first.epilogue.logging.errors.ErrorHandler; +import edu.wpi.first.epilogue.logging.errors.ErrorPrinter; +import edu.wpi.first.networktables.NetworkTableInstance; + +/** + * A configuration object to be used by the generated {@code Epilogue} class to customize its + * behavior. + */ +@SuppressWarnings("checkstyle:MemberName") +public class EpilogueConfiguration { + /** + * The data logger implementation for Epilogue to use. By default, this will log data directly to + * NetworkTables. NetworkTable data can be mirrored to a log file on disk by calling {@code + * DataLogManager.start()} in your {@code robotInit} method. + */ + public DataLogger dataLogger = new NTDataLogger(NetworkTableInstance.getDefault()); + + /** + * The minimum importance level of data to be logged. Defaults to debug, which logs data of all + * importance levels. Any data tagged with an importance level lower than this will not be logged. + */ + public Logged.Importance minimumImportance = Logged.Importance.DEBUG; + + /** + * The error handler for loggers to use if they encounter an error while logging. Defaults to + * printing an error to the standard output. + */ + public ErrorHandler errorHandler = new ErrorPrinter(); + + /** + * The root identifier to use for all logged data. Defaults to "Robot", but can be changed to any + * string. + */ + public String root = "Robot"; +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/Logged.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/Logged.java new file mode 100644 index 00000000000..94762fc03d5 --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/Logged.java @@ -0,0 +1,92 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue; + +import java.lang.annotation.ElementType; +import java.lang.annotation.Retention; +import java.lang.annotation.RetentionPolicy; +import java.lang.annotation.Target; + +/** + * Place this annotation on a class to automatically log every field and every public accessor + * method (methods with no arguments and return a loggable data type). Use {@link #strategy()} to + * flag a class as logging everything it can, except for those elements tagged with + * {@code @Logged(importance = NONE)}; or for logging only specific items also tagged with + * {@code @Logged}. + * + *

Logged fields may have any access modifier. Logged methods must be public; non-public methods + * will be ignored. + * + *

Epilogue can log all primitive types, arrays of primitive types (except char and short), + * Strings, arrays of Strings, sendable objects, objects with a struct serializer, and arrays of + * objects with struct serializers. + */ +@Retention(RetentionPolicy.RUNTIME) +@Target({ElementType.FIELD, ElementType.METHOD, ElementType.TYPE}) +public @interface Logged { + /** + * The name for the annotated element to be logged as. Does nothing on class-level annotations. + * Fields and methods will default to be logged using their in-code names; use this attribute to + * set it to something custom. + * + *

If the annotation is placed on a class, the specified name will not change logged data + * (since that uses the names of the specific usages of the class in fields and methods); however, + * it will be used to set the names of the generated logger that Logged will use to log instances + * of the class. This can be used to avoid name conflicts if you have multiple classes with the + * same name, but in different packages, and want to be able to log both. + * + * @return the name to use to log the field or method under; or the name of the generated + * class-specific logger + */ + String name() default ""; + + /** Opt-in or opt-out strategies for logging. */ + enum Strategy { + /** + * Log everything except for those elements explicitly opted out of with the skip = true + * attribute. This is the default behavior. + */ + OPT_OUT, + + /** Log only fields and methods tagged with an {@link Logged} annotation. */ + OPT_IN + } + + /** + * The strategy to use for logging. Only has an effect on annotations on class or interface + * declarations. + * + * @return the strategy to use to determine which fields and methods in the class to log + */ + Strategy strategy() default Strategy.OPT_OUT; + + /** + * Data importance. Can be used at the class level to set the default importance for all data + * points in the class, and can be used on individual fields and methods to set a specific + * importance level overriding the class-level default. + */ + enum Importance { + /** Debug information. Useful for low-level information like raw sensor values. */ + DEBUG, + + /** + * Informational data. Useful for higher-level information like pose estimates or subsystem + * state. + */ + INFO, + + /** Critical data that should always be present in logs. */ + CRITICAL + } + + /** + * The importance of the annotated data. If placed on a class or interface, this will be the + * default importance of all data within that class; this can be overridden on a per-element basis + * by annotating fields and methods with their own {@code @Logged(importance = ...)} annotation. + * + * @return the importance of the annotated element + */ + Importance importance() default Importance.DEBUG; +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/NotLogged.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/NotLogged.java new file mode 100644 index 00000000000..af0d3217b5b --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/NotLogged.java @@ -0,0 +1,18 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue; + +import java.lang.annotation.ElementType; +import java.lang.annotation.Retention; +import java.lang.annotation.RetentionPolicy; +import java.lang.annotation.Target; + +/** + * A field or method annotated as {@code @NotLogged} will be ignored by Epilogue when determining + * the data to log. + */ +@Target({ElementType.FIELD, ElementType.METHOD}) +@Retention(RetentionPolicy.RUNTIME) +public @interface NotLogged {} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/ClassSpecificLogger.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/ClassSpecificLogger.java new file mode 100644 index 00000000000..d5f34b3b75d --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/ClassSpecificLogger.java @@ -0,0 +1,119 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import edu.wpi.first.epilogue.CustomLoggerFor; +import edu.wpi.first.epilogue.logging.errors.ErrorHandler; +import edu.wpi.first.util.sendable.Sendable; +import edu.wpi.first.util.sendable.SendableBuilder; +import java.util.LinkedHashMap; +import java.util.Map; + +/** + * Base class for class-specific generated loggers. Loggers are generated at compile time by the + * Epilogue annotation processor and are used at runtime for zero-overhead data logging. Users may + * also declare custom loggers, annotated with {@link CustomLoggerFor @CustomLoggerFor}, for + * Epilogue to pull in during compile time to use for logging third party types. + * + * @param the type of data supported by the logger + */ +@SuppressWarnings("unused") // Used by generated subclasses +public abstract class ClassSpecificLogger { + private final Class m_clazz; + // TODO: This will hold onto Sendables that are otherwise no longer referenced by a robot program. + // Determine if that's a concern + // Linked hashmap to maintain insert order + private final Map m_sendables = new LinkedHashMap<>(); + + @SuppressWarnings("PMD.RedundantFieldInitializer") + private boolean m_disabled = false; + + /** + * Instantiates the logger. + * + * @param clazz the Java class of objects that can be logged + */ + protected ClassSpecificLogger(Class clazz) { + this.m_clazz = clazz; + } + + /** + * Updates an object's fields in a data log. + * + * @param dataLogger the logger to update + * @param object the object to update in the log + */ + protected abstract void update(DataLogger dataLogger, T object); + + /** + * Attempts to update the data log. Will do nothing if the logger is {@link #disable() disabled}. + * + * @param dataLogger the logger to log data to + * @param object the data object to log + * @param errorHandler the handler to use if logging raised an exception + */ + @SuppressWarnings("PMD.AvoidCatchingGenericException") + public final void tryUpdate(DataLogger dataLogger, T object, ErrorHandler errorHandler) { + if (m_disabled) { + return; + } + + try { + update(dataLogger, object); + } catch (Exception e) { + errorHandler.handle(e, this); + } + } + + /** + * Checks if this logger has been disabled. + * + * @return true if this logger has been disabled by {@link #disable()}, false if not + */ + public final boolean isDisabled() { + return m_disabled; + } + + /** Disables this logger. Any log calls made while disabled will be ignored. */ + public final void disable() { + m_disabled = true; + } + + /** Reenables this logger after being disabled. Has no effect if the logger is already enabled. */ + public final void reenable() { + m_disabled = false; + } + + /** + * Gets the type of the data this logger accepts. + * + * @return the logged data type + */ + public final Class getLoggedType() { + return m_clazz; + } + + /** + * Logs a sendable type. + * + * @param dataLogger the logger to log data into + * @param sendable the sendable object to log + */ + protected void logSendable(DataLogger dataLogger, Sendable sendable) { + if (sendable == null) { + return; + } + + var builder = + m_sendables.computeIfAbsent( + sendable, + s -> { + var b = new LogBackedSendableBuilder(dataLogger); + s.initSendable(b); + return b; + }); + builder.update(); + } +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/DataLogger.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/DataLogger.java new file mode 100644 index 00000000000..a8b6f341682 --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/DataLogger.java @@ -0,0 +1,229 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import edu.wpi.first.units.Measure; +import edu.wpi.first.units.Unit; +import edu.wpi.first.util.struct.Struct; +import java.util.Collection; + +/** A data logger is a generic interface for logging discrete data points. */ +public interface DataLogger { + /** + * Creates a data logger that logs to multiple backends at once. Data reads will still only occur + * once; data is passed to all composed loggers at once. + * + * @param loggers the loggers to compose together + * @return the multi logger + */ + static DataLogger multi(DataLogger... loggers) { + return new MultiLogger(loggers); + } + + /** + * Creates a lazy version of this logger. A lazy logger will only log data to a field when its + * value changes, which can help keep file size and bandwidth usage in check. However, there is an + * additional CPU and memory overhead associated with tracking the current value of every logged + * entry. The most surefire way to reduce CPU and memory usage associated with logging is to log + * fewer things - which can be done by opting out of logging unnecessary data or increasing the + * minimum logged importance level in the Epilogue configuration. + * + * @return the lazy logger + */ + default DataLogger lazy() { + return new LazyLogger(this); + } + + /** + * Gets a logger that can be used to log nested data underneath a specific path. + * + * @param path the path to use for logging nested data under + * @return the sub logger + */ + DataLogger getSubLogger(String path); + + /** + * Logs a 32-bit integer data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, int value); + + /** + * Logs a 64-bit integer data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, long value); + + /** + * Logs a 32-bit floating point data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, float value); + + /** + * Logs a 64-bit floating point data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, double value); + + /** + * Logs a boolean data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, boolean value); + + /** + * Logs a raw byte array data point. NOTE: serializable data should be logged + * using {@link #log(String, Object, Struct)}. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, byte[] value); + + /** + * Logs a 32-bit integer array data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, int[] value); + + /** + * Logs a 64-bit integer array data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, long[] value); + + /** + * Logs a 32-bit floating point array data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, float[] value); + + /** + * Logs a 64-bit floating point array data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, double[] value); + + /** + * Logs a boolean array data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, boolean[] value); + + /** + * Logs a text data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, String value); + + /** + * Logs a string array data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + void log(String identifier, String[] value); + + /** + * Logs a collection of strings data point. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + */ + default void log(String identifier, Collection value) { + log(identifier, value.toArray(String[]::new)); + } + + /** + * Logs a struct-serializable object. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + * @param struct the struct to use to serialize the data + * @param the serializable type + */ + void log(String identifier, S value, Struct struct); + + /** + * Logs an array of struct-serializable objects. + * + * @param identifier the identifier of the data point + * @param value the value of the data point + * @param struct the struct to use to serialize the objects + * @param the serializable type + */ + void log(String identifier, S[] value, Struct struct); + + /** + * Logs a collection of struct-serializable objects. + * + * @param identifier the identifier of the data + * @param value the collection of objects to log + * @param struct the struct to use to serialize the objects + * @param the serializable type + */ + default void log(String identifier, Collection value, Struct struct) { + @SuppressWarnings("unchecked") + S[] array = (S[]) value.toArray(Object[]::new); + log(identifier, array, struct); + } + + /** + * Logs a measurement's value in terms of its base unit. + * + * @param identifier the identifier of the data field + * @param value the new value of the data field + */ + default void log(String identifier, Measure value) { + log(identifier, value.baseUnitMagnitude()); + } + + /** + * Logs a measurement's value in terms of another unit. + * + * @param identifier the identifier of the data field + * @param value the new value of the data field + * @param unit the unit to log the measurement in + * @param the dimension of the unit + */ + default > void log(String identifier, Measure value, U unit) { + log(identifier, value.in(unit)); + } + + /** + * Logs an enum value. The value will appear as a string entry using the name of the enum. + * + * @param identifier the identifier of the data field + * @param value the new value of the data field + */ + default void log(String identifier, Enum value) { + log(identifier, value.name()); + } + + // TODO: Add default methods to support common no-struct no-sendable types like joysticks? +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/FileLogger.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/FileLogger.java new file mode 100644 index 00000000000..9c66bca274b --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/FileLogger.java @@ -0,0 +1,144 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import edu.wpi.first.util.datalog.BooleanArrayLogEntry; +import edu.wpi.first.util.datalog.BooleanLogEntry; +import edu.wpi.first.util.datalog.DataLog; +import edu.wpi.first.util.datalog.DataLogEntry; +import edu.wpi.first.util.datalog.DoubleArrayLogEntry; +import edu.wpi.first.util.datalog.DoubleLogEntry; +import edu.wpi.first.util.datalog.FloatArrayLogEntry; +import edu.wpi.first.util.datalog.FloatLogEntry; +import edu.wpi.first.util.datalog.IntegerArrayLogEntry; +import edu.wpi.first.util.datalog.IntegerLogEntry; +import edu.wpi.first.util.datalog.RawLogEntry; +import edu.wpi.first.util.datalog.StringArrayLogEntry; +import edu.wpi.first.util.datalog.StringLogEntry; +import edu.wpi.first.util.datalog.StructArrayLogEntry; +import edu.wpi.first.util.datalog.StructLogEntry; +import edu.wpi.first.util.struct.Struct; +import java.util.HashMap; +import java.util.Map; +import java.util.function.BiFunction; + +/** A data logger implementation that saves information to a WPILib {@link DataLog} file on disk. */ +public class FileLogger implements DataLogger { + private final DataLog m_dataLog; + private final Map m_entries = new HashMap<>(); + private final Map m_subLoggers = new HashMap<>(); + + /** + * Creates a new file logger. + * + * @param dataLog the data log to save data to + */ + public FileLogger(DataLog dataLog) { + this.m_dataLog = requireNonNullParam(dataLog, "dataLog", "FileLogger"); + } + + @Override + public DataLogger getSubLogger(String path) { + return m_subLoggers.computeIfAbsent(path, k -> new SubLogger(k, this)); + } + + @SuppressWarnings("unchecked") + private E getEntry( + String identifier, BiFunction ctor) { + if (m_entries.get(identifier) != null) { + return (E) m_entries.get(identifier); + } + + var entry = ctor.apply(m_dataLog, identifier); + m_entries.put(identifier, entry); + return entry; + } + + @Override + public void log(String identifier, int value) { + getEntry(identifier, IntegerLogEntry::new).append(value); + } + + @Override + public void log(String identifier, long value) { + getEntry(identifier, IntegerLogEntry::new).append(value); + } + + @Override + public void log(String identifier, float value) { + getEntry(identifier, FloatLogEntry::new).append(value); + } + + @Override + public void log(String identifier, double value) { + getEntry(identifier, DoubleLogEntry::new).append(value); + } + + @Override + public void log(String identifier, boolean value) { + getEntry(identifier, BooleanLogEntry::new).append(value); + } + + @Override + public void log(String identifier, byte[] value) { + getEntry(identifier, RawLogEntry::new).append(value); + } + + @Override + @SuppressWarnings("PMD.UnnecessaryCastRule") + public void log(String identifier, int[] value) { + long[] widened = new long[value.length]; + for (int i = 0; i < value.length; i++) { + widened[i] = (long) value[i]; + } + getEntry(identifier, IntegerArrayLogEntry::new).append(widened); + } + + @Override + public void log(String identifier, long[] value) { + getEntry(identifier, IntegerArrayLogEntry::new).append(value); + } + + @Override + public void log(String identifier, float[] value) { + getEntry(identifier, FloatArrayLogEntry::new).append(value); + } + + @Override + public void log(String identifier, double[] value) { + getEntry(identifier, DoubleArrayLogEntry::new).append(value); + } + + @Override + public void log(String identifier, boolean[] value) { + getEntry(identifier, BooleanArrayLogEntry::new).append(value); + } + + @Override + public void log(String identifier, String value) { + getEntry(identifier, StringLogEntry::new).append(value); + } + + @Override + public void log(String identifier, String[] value) { + getEntry(identifier, StringArrayLogEntry::new).append(value); + } + + @Override + @SuppressWarnings("unchecked") + public void log(String identifier, S value, Struct struct) { + m_dataLog.addSchema(struct); + getEntry(identifier, (log, k) -> StructLogEntry.create(log, k, struct)).append(value); + } + + @Override + @SuppressWarnings("unchecked") + public void log(String identifier, S[] value, Struct struct) { + m_dataLog.addSchema(struct); + getEntry(identifier, (log, k) -> StructArrayLogEntry.create(log, k, struct)).append(value); + } +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LazyLogger.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LazyLogger.java new file mode 100644 index 00000000000..6e99aa5c305 --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LazyLogger.java @@ -0,0 +1,240 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import edu.wpi.first.util.struct.Struct; +import java.util.Arrays; +import java.util.HashMap; +import java.util.Map; +import java.util.Objects; + +/** + * A data logger implementation that only logs data when it changes. Useful for keeping bandwidth + * and file sizes down. However, because it still needs to check that data has changed, it cannot + * avoid expensive sensor reads. + */ +public class LazyLogger implements DataLogger { + private final DataLogger m_logger; + + // Keep a record of the most recent value written to each entry + // Note that this may duplicate a lot of data, and will box primitives. + private final Map m_previousValues = new HashMap<>(); + private final Map m_subLoggers = new HashMap<>(); + + /** + * Creates a new lazy logger wrapper around another logger. + * + * @param logger the logger to delegate to + */ + public LazyLogger(DataLogger logger) { + this.m_logger = logger; + } + + @Override + public DataLogger lazy() { + // Already lazy, don't need to wrap it again + return this; + } + + @Override + public DataLogger getSubLogger(String path) { + return m_subLoggers.computeIfAbsent(path, k -> new SubLogger(k, this)); + } + + @Override + public void log(String identifier, int value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof Integer oldValue && oldValue == value) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, long value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof Long oldValue && oldValue == value) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, float value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof Float oldValue && oldValue == value) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, double value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof Double oldValue && oldValue == value) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, boolean value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof Boolean oldValue && oldValue == value) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, byte[] value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof byte[] oldValue && Arrays.equals(oldValue, value)) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, int[] value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof int[] oldValue && Arrays.equals(oldValue, value)) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, long[] value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof long[] oldValue && Arrays.equals(oldValue, value)) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, float[] value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof float[] oldValue && Arrays.equals(oldValue, value)) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, double[] value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof double[] oldValue && Arrays.equals(oldValue, value)) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, boolean[] value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof boolean[] oldValue && Arrays.equals(oldValue, value)) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, String value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof String oldValue && oldValue.equals(value)) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, String[] value) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof String[] oldValue && Arrays.equals(oldValue, value)) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value); + } + + @Override + public void log(String identifier, S value, Struct struct) { + var previous = m_previousValues.get(identifier); + + if (Objects.equals(previous, value)) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value, struct); + } + + @Override + public void log(String identifier, S[] value, Struct struct) { + var previous = m_previousValues.get(identifier); + + if (previous instanceof Object[] oldValue && Arrays.equals(oldValue, value)) { + // no change + return; + } + + m_previousValues.put(identifier, value); + m_logger.log(identifier, value, struct); + } +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LogBackedSendableBuilder.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LogBackedSendableBuilder.java new file mode 100644 index 00000000000..aa71dbbf977 --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/LogBackedSendableBuilder.java @@ -0,0 +1,212 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import edu.wpi.first.util.function.BooleanConsumer; +import edu.wpi.first.util.function.FloatConsumer; +import edu.wpi.first.util.function.FloatSupplier; +import edu.wpi.first.util.sendable.SendableBuilder; +import java.util.ArrayList; +import java.util.Collection; +import java.util.function.BooleanSupplier; +import java.util.function.Consumer; +import java.util.function.DoubleConsumer; +import java.util.function.DoubleSupplier; +import java.util.function.LongConsumer; +import java.util.function.LongSupplier; +import java.util.function.Supplier; + +/** A sendable builder implementation that sends data to a {@link DataLogger}. */ +@SuppressWarnings("PMD.CouplingBetweenObjects") // most methods simply delegate to the logger +public class LogBackedSendableBuilder implements SendableBuilder { + private final DataLogger m_logger; + private final Collection m_updates = new ArrayList<>(); + + /** + * Creates a new sendable builder that delegates writes to an underlying data logger. + * + * @param logger the data logger to write the sendable data to + */ + public LogBackedSendableBuilder(DataLogger logger) { + this.m_logger = logger; + } + + @Override + public void setSmartDashboardType(String type) { + m_logger.log(".type", type); + } + + @Override + public void setActuator(boolean value) { + // ignore + } + + @Override + public void setSafeState(Runnable func) { + // ignore + } + + @Override + public void addBooleanProperty(String key, BooleanSupplier getter, BooleanConsumer setter) { + m_updates.add(() -> m_logger.log(key, getter.getAsBoolean())); + } + + @Override + public void publishConstBoolean(String key, boolean value) { + m_logger.log(key, value); + } + + @Override + public void addIntegerProperty(String key, LongSupplier getter, LongConsumer setter) { + m_updates.add(() -> m_logger.log(key, getter.getAsLong())); + } + + @Override + public void publishConstInteger(String key, long value) { + m_logger.log(key, value); + } + + @Override + public void addFloatProperty(String key, FloatSupplier getter, FloatConsumer setter) { + m_updates.add(() -> m_logger.log(key, getter.getAsFloat())); + } + + @Override + public void publishConstFloat(String key, float value) { + m_logger.log(key, value); + } + + @Override + public void addDoubleProperty(String key, DoubleSupplier getter, DoubleConsumer setter) { + m_updates.add(() -> m_logger.log(key, getter.getAsDouble())); + } + + @Override + public void publishConstDouble(String key, double value) { + m_logger.log(key, value); + } + + @Override + public void addStringProperty(String key, Supplier getter, Consumer setter) { + if (getter != null) { + m_updates.add(() -> m_logger.log(key, getter.get())); + } + } + + @Override + public void publishConstString(String key, String value) { + m_logger.log(key, value); + } + + @Override + public void addBooleanArrayProperty( + String key, Supplier getter, Consumer setter) { + if (getter != null) { + m_updates.add(() -> m_logger.log(key, getter.get())); + } + } + + @Override + public void publishConstBooleanArray(String key, boolean[] value) { + m_logger.log(key, value); + } + + @Override + public void addIntegerArrayProperty( + String key, Supplier getter, Consumer setter) { + if (getter != null) { + m_updates.add(() -> m_logger.log(key, getter.get())); + } + } + + @Override + public void publishConstIntegerArray(String key, long[] value) { + m_logger.log(key, value); + } + + @Override + public void addFloatArrayProperty( + String key, Supplier getter, Consumer setter) { + if (getter != null) { + m_updates.add(() -> m_logger.log(key, getter.get())); + } + } + + @Override + public void publishConstFloatArray(String key, float[] value) { + m_logger.log(key, value); + } + + @Override + public void addDoubleArrayProperty( + String key, Supplier getter, Consumer setter) { + if (getter != null) { + m_updates.add(() -> m_logger.log(key, getter.get())); + } + } + + @Override + public void publishConstDoubleArray(String key, double[] value) { + m_logger.log(key, value); + } + + @Override + public void addStringArrayProperty( + String key, Supplier getter, Consumer setter) { + if (getter != null) { + m_updates.add(() -> m_logger.log(key, getter.get())); + } + } + + @Override + public void publishConstStringArray(String key, String[] value) { + m_logger.log(key, value); + } + + @Override + public void addRawProperty( + String key, String typeString, Supplier getter, Consumer setter) { + if (getter != null) { + m_updates.add(() -> m_logger.log(key, getter.get())); + } + } + + @Override + public void publishConstRaw(String key, String typeString, byte[] value) { + m_logger.log(key, value); + } + + @Override + public BackendKind getBackendKind() { + return BackendKind.kUnknown; + } + + @Override + public boolean isPublished() { + return true; + } + + @Override + public void update() { + for (Runnable update : m_updates) { + update.run(); + } + } + + @Override + public void clearProperties() { + m_updates.clear(); + } + + @Override + public void addCloseable(AutoCloseable closeable) { + // Ignore + } + + @Override + public void close() throws Exception { + clearProperties(); + } +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/MultiLogger.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/MultiLogger.java new file mode 100644 index 00000000000..b7ad348d759 --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/MultiLogger.java @@ -0,0 +1,134 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import edu.wpi.first.util.struct.Struct; +import java.util.HashMap; +import java.util.List; +import java.util.Map; + +/** + * A data logger implementation that delegates to other loggers. Helpful for simultaneous logging to + * multiple data stores at once. + */ +public class MultiLogger implements DataLogger { + private final List m_loggers; + private final Map m_subLoggers = new HashMap<>(); + + // Use DataLogger.multi(...) instead of instantiation directly + MultiLogger(DataLogger... loggers) { + this.m_loggers = List.of(loggers); + } + + @Override + public DataLogger getSubLogger(String path) { + return m_subLoggers.computeIfAbsent(path, k -> new SubLogger(k, this)); + } + + @Override + public void log(String identifier, int value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, long value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, float value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, double value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, boolean value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, byte[] value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, int[] value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, long[] value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, float[] value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, double[] value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, boolean[] value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, String value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, String[] value) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value); + } + } + + @Override + public void log(String identifier, S value, Struct struct) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value, struct); + } + } + + @Override + public void log(String identifier, S[] value, Struct struct) { + for (DataLogger logger : m_loggers) { + logger.log(identifier, value, struct); + } + } +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NTDataLogger.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NTDataLogger.java new file mode 100644 index 00000000000..881d7f7c5e2 --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NTDataLogger.java @@ -0,0 +1,167 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import edu.wpi.first.networktables.BooleanArrayPublisher; +import edu.wpi.first.networktables.BooleanPublisher; +import edu.wpi.first.networktables.DoubleArrayPublisher; +import edu.wpi.first.networktables.DoublePublisher; +import edu.wpi.first.networktables.FloatArrayPublisher; +import edu.wpi.first.networktables.FloatPublisher; +import edu.wpi.first.networktables.IntegerArrayPublisher; +import edu.wpi.first.networktables.IntegerPublisher; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.networktables.Publisher; +import edu.wpi.first.networktables.RawPublisher; +import edu.wpi.first.networktables.StringArrayPublisher; +import edu.wpi.first.networktables.StringPublisher; +import edu.wpi.first.networktables.StructArrayPublisher; +import edu.wpi.first.networktables.StructPublisher; +import edu.wpi.first.util.struct.Struct; +import java.util.HashMap; +import java.util.Map; + +/** + * A data logger implementation that sends data over network tables. Be careful when using this, + * since sending too much data may cause bandwidth or CPU starvation. + */ +public class NTDataLogger implements DataLogger { + private final NetworkTableInstance m_nt; + + private final Map m_publishers = new HashMap<>(); + private final Map m_subLoggers = new HashMap<>(); + + /** + * Creates a data logger that sends information to NetworkTables. + * + * @param nt the NetworkTable instance to use to send data to + */ + public NTDataLogger(NetworkTableInstance nt) { + this.m_nt = nt; + } + + @Override + public DataLogger getSubLogger(String path) { + return m_subLoggers.computeIfAbsent(path, k -> new SubLogger(k, this)); + } + + @Override + public void log(String identifier, int value) { + ((IntegerPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getIntegerTopic(k).publish())) + .set(value); + } + + @Override + public void log(String identifier, long value) { + ((IntegerPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getIntegerTopic(k).publish())) + .set(value); + } + + @Override + public void log(String identifier, float value) { + ((FloatPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getFloatTopic(k).publish())) + .set(value); + } + + @Override + public void log(String identifier, double value) { + ((DoublePublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getDoubleTopic(k).publish())) + .set(value); + } + + @Override + public void log(String identifier, boolean value) { + ((BooleanPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getBooleanTopic(k).publish())) + .set(value); + } + + @Override + public void log(String identifier, byte[] value) { + ((RawPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getRawTopic(k).publish("raw"))) + .set(value); + } + + @Override + @SuppressWarnings("PMD.UnnecessaryCastRule") + public void log(String identifier, int[] value) { + // NT backend only supports int64[], so we have to manually widen to 64 bits before sending + long[] widened = new long[value.length]; + + for (int i = 0; i < value.length; i++) { + widened[i] = (long) value[i]; + } + + ((IntegerArrayPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getIntegerArrayTopic(k).publish())) + .set(widened); + } + + @Override + public void log(String identifier, long[] value) { + ((IntegerArrayPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getIntegerArrayTopic(k).publish())) + .set(value); + } + + @Override + public void log(String identifier, float[] value) { + ((FloatArrayPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getFloatArrayTopic(k).publish())) + .set(value); + } + + @Override + public void log(String identifier, double[] value) { + ((DoubleArrayPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getDoubleArrayTopic(k).publish())) + .set(value); + } + + @Override + public void log(String identifier, boolean[] value) { + ((BooleanArrayPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getBooleanArrayTopic(k).publish())) + .set(value); + } + + @Override + public void log(String identifier, String value) { + ((StringPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getStringTopic(k).publish())) + .set(value); + } + + @Override + public void log(String identifier, String[] value) { + ((StringArrayPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getStringArrayTopic(k).publish())) + .set(value); + } + + @Override + @SuppressWarnings("unchecked") + public void log(String identifier, S value, Struct struct) { + m_nt.addSchema(struct); + ((StructPublisher) + m_publishers.computeIfAbsent(identifier, k -> m_nt.getStructTopic(k, struct).publish())) + .set(value); + } + + @Override + @SuppressWarnings("unchecked") + public void log(String identifier, S[] value, Struct struct) { + m_nt.addSchema(struct); + ((StructArrayPublisher) + m_publishers.computeIfAbsent( + identifier, k -> m_nt.getStructArrayTopic(k, struct).publish())) + .set(value); + } +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NullLogger.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NullLogger.java new file mode 100644 index 00000000000..fb6d30474b9 --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NullLogger.java @@ -0,0 +1,62 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import edu.wpi.first.util.struct.Struct; + +/** Null data logger implementation that logs nothing. */ +public class NullLogger implements DataLogger { + @Override + public DataLogger getSubLogger(String path) { + // Since a sublogger would still log nothing and has no state, we can just return the same + // null-logging implementation + return this; + } + + @Override + public void log(String identifier, int value) {} + + @Override + public void log(String identifier, long value) {} + + @Override + public void log(String identifier, float value) {} + + @Override + public void log(String identifier, double value) {} + + @Override + public void log(String identifier, boolean value) {} + + @Override + public void log(String identifier, byte[] value) {} + + @Override + public void log(String identifier, int[] value) {} + + @Override + public void log(String identifier, long[] value) {} + + @Override + public void log(String identifier, float[] value) {} + + @Override + public void log(String identifier, double[] value) {} + + @Override + public void log(String identifier, boolean[] value) {} + + @Override + public void log(String identifier, String value) {} + + @Override + public void log(String identifier, String[] value) {} + + @Override + public void log(String identifier, S value, Struct struct) {} + + @Override + public void log(String identifier, S[] value, Struct struct) {} +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/SubLogger.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/SubLogger.java new file mode 100644 index 00000000000..cb5a48ea1af --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/SubLogger.java @@ -0,0 +1,115 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import edu.wpi.first.util.struct.Struct; +import java.util.HashMap; +import java.util.Map; + +/** + * A data logger that logs to an underlying logger, prepending all logged data with a specific + * prefix. Useful for logging nested data structures. + */ +public class SubLogger implements DataLogger { + private final String m_prefix; + private final DataLogger m_impl; + private final Map m_subLoggers = new HashMap<>(); + + /** + * Creates a new sublogger underneath another logger. + * + * @param prefix the prefix to append to all data logged in the sublogger + * @param impl the data logger to log to + */ + public SubLogger(String prefix, DataLogger impl) { + // Add a trailing slash if not already present + if (prefix.endsWith("/")) { + this.m_prefix = prefix; + } else { + this.m_prefix = prefix + "/"; + } + this.m_impl = impl; + } + + @Override + public DataLogger getSubLogger(String path) { + return m_subLoggers.computeIfAbsent(path, k -> new SubLogger(k, this)); + } + + @Override + public void log(String identifier, int value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, long value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, float value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, double value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, boolean value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, byte[] value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, int[] value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, long[] value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, float[] value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, double[] value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, boolean[] value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, String value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, String[] value) { + m_impl.log(m_prefix + identifier, value); + } + + @Override + public void log(String identifier, S value, Struct struct) { + m_impl.log(m_prefix + identifier, value, struct); + } + + @Override + public void log(String identifier, S[] value, Struct struct) { + m_impl.log(m_prefix + identifier, value, struct); + } +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/CrashOnError.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/CrashOnError.java new file mode 100644 index 00000000000..63a68d0852d --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/CrashOnError.java @@ -0,0 +1,22 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging.errors; + +import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + +/** + * An error handler implementation that will throw an exception if logging raised an exception. This + * is useful when running code in simulation or in JUnit tests to quickly identify errors in your + * code. + */ +public class CrashOnError implements ErrorHandler { + @Override + public void handle(Throwable exception, ClassSpecificLogger logger) { + throw new RuntimeException( + "[EPILOGUE] An error occurred while logging an instance of " + + logger.getLoggedType().getName(), + exception); + } +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorHandler.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorHandler.java new file mode 100644 index 00000000000..910de790897 --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorHandler.java @@ -0,0 +1,61 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging.errors; + +import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + +/** + * An error handler is used by the Logged framework to catch and process any errors that occur + * during the logging process. Different handlers can be used in different operating modes, such as + * crashing in simulation to identify errors before they make it to a robot, or automatically + * disabling loggers if they encounter too many errors on the field to let the robot keep running + * while playing a match. + */ +@FunctionalInterface +public interface ErrorHandler { + /** + * Handles an exception that arose while logging. + * + * @param exception the exception that occurred + * @param logger the logger that was being processed that caused the error to occur + */ + void handle(Throwable exception, ClassSpecificLogger logger); + + /** + * Creates an error handler that will immediately re-throw an exception and cause robot code to + * exit. This is particularly useful when running in simulation or JUnit tests to identify errors + * quickly and safely. + * + * @return the error handler + */ + static ErrorHandler crashOnError() { + return new CrashOnError(); + } + + /** + * Creates an error handler that will print error messages to the console output, but otherwise + * allow logging to continue in the future. This can be helpful when errors occur only rarely and + * you don't want your robot program to crash or disable future logging. + * + * @return the error handler + */ + static ErrorHandler printErrorMessages() { + return new ErrorPrinter(); + } + + /** + * Creates an error handler that will automatically disable a logger if it encounters too many + * errors. Only the error-prone logger(s) will be disabled; loggers that have not encountered any + * errors, or encountered fewer than the limit, will continue to be used. Disabled loggers can be + * reset by calling {@link LoggerDisabler#reset()} on the handler. + * + * @param maximumPermissibleErrors the maximum number of errors that a logger is permitted to + * encounter before being disabled. + * @return the error handler + */ + static LoggerDisabler disabling(int maximumPermissibleErrors) { + return LoggerDisabler.forLimit(maximumPermissibleErrors); + } +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorPrinter.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorPrinter.java new file mode 100644 index 00000000000..4987994f9ed --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorPrinter.java @@ -0,0 +1,19 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging.errors; + +import edu.wpi.first.epilogue.logging.ClassSpecificLogger; + +/** An error handler implementation that prints error information to the console. */ +public class ErrorPrinter implements ErrorHandler { + @Override + public void handle(Throwable exception, ClassSpecificLogger logger) { + System.err.println( + "[EPILOGUE] An error occurred while logging an instance of " + + logger.getLoggedType().getName() + + ": " + + exception.getMessage()); + } +} diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/LoggerDisabler.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/LoggerDisabler.java new file mode 100644 index 00000000000..99b20aa4b24 --- /dev/null +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/LoggerDisabler.java @@ -0,0 +1,69 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging.errors; + +import edu.wpi.first.epilogue.logging.ClassSpecificLogger; +import java.util.HashMap; +import java.util.Map; + +/** + * An error handler that disables loggers after too many exceptions are raised. Useful when playing + * in matches, where data logging is less important than reliable control. Setting the threshold to + * ≤0 will cause any logger that encounters an exception whilst logging to immediately be disabled. + * Setting to higher values means your program is more tolerant of errors, but takes longer to + * disable, and therefore may have more sets of partial or incomplete data and may have more CPU + * overhead due to the cost of throwing exceptions. + */ +public class LoggerDisabler implements ErrorHandler { + private final int m_threshold; + private final Map, Integer> m_errorCounts = new HashMap<>(); + + /** + * Creates a new logger-disabling error handler. + * + * @param threshold how many errors any one logger is allowed to encounter before it is disabled. + */ + public LoggerDisabler(int threshold) { + this.m_threshold = threshold; + } + + /** + * Creates a disabler that kicks in after a logger raises more than {@code threshold} exceptions. + * + * @param threshold the threshold value for the maximum number of exceptions loggers are permitted + * to encounter before they are disabled + * @return the disabler + */ + public static LoggerDisabler forLimit(int threshold) { + return new LoggerDisabler(threshold); + } + + @Override + public void handle(Throwable exception, ClassSpecificLogger logger) { + var errorCount = m_errorCounts.getOrDefault(logger, 0) + 1; + m_errorCounts.put(logger, errorCount); + + if (errorCount > m_threshold) { + logger.disable(); + System.err.println( + "[EPILOGUE] Too many errors detected in " + + logger.getClass().getName() + + " (maximum allowed: " + + m_threshold + + "). The most recent error follows:"); + System.err.println(exception.getMessage()); + exception.printStackTrace(System.err); + } + } + + /** Resets all error counts and reenables all loggers. */ + public void reset() { + for (var logger : m_errorCounts.keySet()) { + // Safe. This is a no-op on loggers that are already enabled + logger.reenable(); + } + m_errorCounts.clear(); + } +} diff --git a/epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/ClassSpecificLoggerTest.java b/epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/ClassSpecificLoggerTest.java new file mode 100644 index 00000000000..1688f587eb9 --- /dev/null +++ b/epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/ClassSpecificLoggerTest.java @@ -0,0 +1,44 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import static org.junit.jupiter.api.Assertions.assertEquals; + +import edu.wpi.first.epilogue.Logged; +import java.util.List; +import org.junit.jupiter.api.Test; + +class ClassSpecificLoggerTest { + @Logged + record Point2d(double x, double y, int dim) { + static class Logger extends ClassSpecificLogger { + Logger() { + super(Point2d.class); + } + + @Override + protected void update(DataLogger dataLogger, Point2d object) { + dataLogger.log("x", object.x); + dataLogger.log("y", object.y); + dataLogger.log("dim", object.dim); + } + } + } + + @Test + void testReadPrivate() { + var point = new Point2d(1, 4, 2); + var logger = new Point2d.Logger(); + var dataLog = new TestLogger(); + logger.update(dataLog.getSubLogger("Point"), point); + + assertEquals( + List.of( + new TestLogger.LogEntry<>("Point/x", 1.0), + new TestLogger.LogEntry<>("Point/y", 4.0), + new TestLogger.LogEntry<>("Point/dim", 2)), + dataLog.getEntries()); + } +} diff --git a/epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/LazyLoggerTest.java b/epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/LazyLoggerTest.java new file mode 100644 index 00000000000..6fe07a7154a --- /dev/null +++ b/epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/LazyLoggerTest.java @@ -0,0 +1,56 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertSame; + +import java.util.List; +import org.junit.jupiter.api.Test; + +class LazyLoggerTest { + @Test + void lazyOfLazyReturnsSelf() { + var lazy = new LazyLogger(new NullLogger()); + assertSame(lazy, lazy.lazy()); + } + + @Test + void lazyInt() { + var logger = new TestLogger(); + var lazy = new LazyLogger(logger); + + { + // First time logging to "int" should go through + lazy.log("int", 0); + assertEquals(List.of(new TestLogger.LogEntry<>("int", 0)), logger.getEntries()); + } + + { + // Logging the current value shouldn't go through + lazy.log("int", 0); + assertEquals(List.of(new TestLogger.LogEntry<>("int", 0)), logger.getEntries()); + } + + { + // Logging a new value should go through + lazy.log("int", 1); + assertEquals( + List.of(new TestLogger.LogEntry<>("int", 0), new TestLogger.LogEntry<>("int", 1)), + logger.getEntries()); + } + + { + // Logging a previous value should go through + lazy.log("int", 0); + assertEquals( + List.of( + new TestLogger.LogEntry<>("int", 0), + new TestLogger.LogEntry<>("int", 1), + new TestLogger.LogEntry<>("int", 0)), + logger.getEntries()); + } + } +} diff --git a/epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/TestLogger.java b/epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/TestLogger.java new file mode 100644 index 00000000000..1dc8547ed79 --- /dev/null +++ b/epilogue-runtime/src/test/java/edu/wpi/first/epilogue/logging/TestLogger.java @@ -0,0 +1,109 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.epilogue.logging; + +import edu.wpi.first.util.struct.Struct; +import edu.wpi.first.util.struct.StructBuffer; +import java.util.ArrayList; +import java.util.HashMap; +import java.util.List; +import java.util.Map; + +@SuppressWarnings("PMD.TestClassWithoutTestCases") // This is not a test class! +public class TestLogger implements DataLogger { + public record LogEntry(String identifier, T value) {} + + private final Map m_subLoggers = new HashMap<>(); + + private final List> m_entries = new ArrayList<>(); + + public List> getEntries() { + return m_entries; + } + + @Override + public DataLogger getSubLogger(String path) { + return m_subLoggers.computeIfAbsent(path, k -> new SubLogger(k, this)); + } + + @Override + public void log(String identifier, int value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, long value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, float value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, double value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, boolean value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, byte[] value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, int[] value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, long[] value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, float[] value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, double[] value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, boolean[] value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, String value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, String[] value) { + m_entries.add(new LogEntry<>(identifier, value)); + } + + @Override + public void log(String identifier, S value, Struct struct) { + var serialized = StructBuffer.create(struct).write(value).array(); + + m_entries.add(new LogEntry<>(identifier, serialized)); + } + + @Override + public void log(String identifier, S[] value, Struct struct) { + var serialized = StructBuffer.create(struct).writeArray(value).array(); + + m_entries.add(new LogEntry<>(identifier, serialized)); + } +} diff --git a/settings.gradle b/settings.gradle index 0ce2398ca60..7d63645cd50 100644 --- a/settings.gradle +++ b/settings.gradle @@ -58,6 +58,8 @@ include 'msvcruntime' include 'ntcoreffi' include 'apriltag' include 'processstarter' +include 'epilogue-processor' +include 'epilogue-runtime' buildCache { def cred = { diff --git a/shared/java/javacommon.gradle b/shared/java/javacommon.gradle index 46ad707bb60..5d0cae57910 100644 --- a/shared/java/javacommon.gradle +++ b/shared/java/javacommon.gradle @@ -113,6 +113,8 @@ tasks.withType(JavaCompile).configureEach { "-Xlint:-try", // ignore missing serialVersionUID warnings "-Xlint:-serial", + // ignore unclaimed annotation warning from annotation processing + "-Xlint:-processing", ] } diff --git a/wpilibjExamples/build.gradle b/wpilibjExamples/build.gradle index 37b6d95cc95..e549e5d9ff8 100644 --- a/wpilibjExamples/build.gradle +++ b/wpilibjExamples/build.gradle @@ -24,6 +24,8 @@ dependencies { implementation project(':wpilibNewCommands') implementation project(':romiVendordep') implementation project(':xrpVendordep') + implementation project(':epilogue-runtime') + annotationProcessor project(':epilogue-processor') testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1' testRuntimeOnly 'org.junit.platform:junit-platform-launcher' diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java index 88b1913aa09..4c8ffbcd563 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java @@ -6,6 +6,7 @@ import static edu.wpi.first.wpilibj2.command.Commands.parallel; +import edu.wpi.first.epilogue.Logged; import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.AutoConstants; import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.OIConstants; import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.ShooterConstants; @@ -24,6 +25,7 @@ * periodic methods (other than the scheduler calls). Instead, the structure of the robot (including * subsystems, commands, and button mappings) should be declared here. */ +@Logged(name = "Rapid React Command Robot Container") public class RapidReactCommandBot { // The robot's subsystems private final Drive m_drive = new Drive(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java index 3588677ba47..049798cad6d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java @@ -4,6 +4,9 @@ package edu.wpi.first.wpilibj.examples.rapidreactcommandbot; +import edu.wpi.first.epilogue.Epilogue; +import edu.wpi.first.epilogue.Logged; +import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; @@ -14,6 +17,7 @@ * the package after creating this project, you must also update the build.gradle file in the * project. */ +@Logged(name = "Rapid React Command Robot") public class Robot extends TimedRobot { private Command m_autonomousCommand; @@ -27,6 +31,10 @@ public class Robot extends TimedRobot { public void robotInit() { // Configure default commands and condition bindings on robot startup m_robot.configureBindings(); + + // Initialize data logging. + DataLogManager.start(); + Epilogue.bind(this); } /** diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java index dd7854d15ff..18f12001ca6 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java @@ -4,6 +4,8 @@ package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems; +import edu.wpi.first.epilogue.Logged; +import edu.wpi.first.epilogue.NotLogged; import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -13,6 +15,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import java.util.function.DoubleSupplier; +@Logged public class Drive extends SubsystemBase { // The motors on the left side of the drive. private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); @@ -23,6 +26,7 @@ public class Drive extends SubsystemBase { private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); // The robot's drive + @NotLogged // Would duplicate motor data, there's no point sending it twice private final DifferentialDrive m_drive = new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java index 0f242dfae01..d6b841962aa 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java @@ -6,12 +6,14 @@ import static edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.IntakeConstants; +import edu.wpi.first.epilogue.Logged; import edu.wpi.first.wpilibj.DoubleSolenoid; import edu.wpi.first.wpilibj.PneumaticsModuleType; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; +@Logged public class Intake extends SubsystemBase { private final PWMSparkMax m_motor = new PWMSparkMax(IntakeConstants.kMotorPort); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java index b51562fca87..fd35d5f64a2 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java @@ -4,14 +4,15 @@ package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems; +import edu.wpi.first.epilogue.Logged; import edu.wpi.first.wpilibj.AnalogPotentiometer; import edu.wpi.first.wpilibj.Compressor; import edu.wpi.first.wpilibj.PneumaticsModuleType; -import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; /** Subsystem for managing the compressor, pressure sensor, etc. */ +@Logged public class Pneumatics extends SubsystemBase { // External analog pressure sensor // product-specific voltage->pressure conversion, see product manual @@ -26,17 +27,12 @@ public class Pneumatics extends SubsystemBase { // Compressor connected to a PCM with a default CAN ID (0) private final Compressor m_compressor = new Compressor(PneumaticsModuleType.CTREPCM); - public Pneumatics() { - var tab = Shuffleboard.getTab("Pneumatics"); - tab.addDouble("External Pressure [PSI]", this::getPressure); - } - /** * Query the analog pressure sensor. * * @return the measured pressure, in PSI */ - private double getPressure() { + public double getPressure() { // Get the pressure (in PSI) from an analog pressure sensor connected to the RIO. return m_pressureTransducer.get(); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java index 88d564beb3c..a10f6f91436 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java @@ -9,6 +9,7 @@ import static edu.wpi.first.wpilibj2.command.Commands.parallel; import static edu.wpi.first.wpilibj2.command.Commands.waitUntil; +import edu.wpi.first.epilogue.Logged; import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.wpilibj.Encoder; @@ -17,6 +18,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; +@Logged public class Shooter extends SubsystemBase { private final PWMSparkMax m_shooterMotor = new PWMSparkMax(ShooterConstants.kShooterMotorPort); private final PWMSparkMax m_feederMotor = new PWMSparkMax(ShooterConstants.kFeederMotorPort); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java index f3812b1d894..db4611e5e81 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java @@ -4,6 +4,8 @@ package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems; +import edu.wpi.first.epilogue.Logged; +import edu.wpi.first.epilogue.NotLogged; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.StorageConstants; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; @@ -11,13 +13,16 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.button.Trigger; +@Logged public class Storage extends SubsystemBase { private final PWMSparkMax m_motor = new PWMSparkMax(StorageConstants.kMotorPort); + @NotLogged // We'll log a more meaningful boolean instead private final DigitalInput m_ballSensor = new DigitalInput(StorageConstants.kBallSensorPort); // Expose trigger from subsystem to improve readability and ease // inter-subsystem communications /** Whether the ball storage is full. */ + @Logged(name = "Has Cargo") @SuppressWarnings("checkstyle:MemberName") public final Trigger hasCargo = new Trigger(m_ballSensor::get); From e5b7cf4c7670b4b4d842306aed086ecb205329f9 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Tue, 16 Jul 2024 20:26:35 -0400 Subject: [PATCH 07/10] [hal] Fix interrupt edges being flipped in sim (#6720) --- hal/src/main/native/sim/Interrupts.cpp | 40 +++++----- wpilibc/src/test/native/cpp/InterruptTest.cpp | 62 ++++++++++++++- .../edu/wpi/first/wpilibj/InterruptTest.java | 78 ++++++++++++++++++- 3 files changed, 160 insertions(+), 20 deletions(-) diff --git a/hal/src/main/native/sim/Interrupts.cpp b/hal/src/main/native/sim/Interrupts.cpp index ac9f7f8ebb6..1537c73640a 100644 --- a/hal/src/main/native/sim/Interrupts.cpp +++ b/hal/src/main/native/sim/Interrupts.cpp @@ -44,7 +44,7 @@ struct Interrupt { HAL_AnalogTriggerType trigType; int64_t risingTimestamp; int64_t fallingTimestamp; - bool previousState; + bool currentState; bool fireOnUp; bool fireOnDown; int32_t callbackId; @@ -121,8 +121,8 @@ static void ProcessInterruptDigitalSynchronous(const char* name, void* param, return; } bool retVal = value->data.v_boolean; - auto previousState = interrupt->previousState; - interrupt->previousState = retVal; + auto previousState = interrupt->currentState; + interrupt->currentState = retVal; // If no change in interrupt, return; if (retVal == previousState) { return; @@ -176,8 +176,8 @@ static void ProcessInterruptAnalogSynchronous(const char* name, void* param, // Pulse interrupt interruptData->waitCond.notify_all(); } - auto previousState = interrupt->previousState; - interrupt->previousState = retVal; + auto previousState = interrupt->currentState; + interrupt->currentState = retVal; // If no change in interrupt, return; if (retVal == previousState) { return; @@ -220,7 +220,7 @@ static int64_t WaitForInterruptDigital(HAL_InterruptHandle handle, return WaitResult::Timeout; } - interrupt->previousState = SimDIOData[digitalIndex].value; + interrupt->currentState = SimDIOData[digitalIndex].value; int32_t uid = SimDIOData[digitalIndex].value.RegisterCallback( &ProcessInterruptDigitalSynchronous, @@ -252,14 +252,16 @@ static int64_t WaitForInterruptDigital(HAL_InterruptHandle handle, if (timedOut) { return WaitResult::Timeout; } - // True => false, Falling - if (interrupt->previousState) { + // We know the value has changed because we would've timed out otherwise. + // If the current state is true, the previous state was false, so this is a + // rising edge. Otherwise, it's a falling edge. + if (interrupt->currentState) { // Set our return value and our timestamps - interrupt->fallingTimestamp = hal::GetFPGATime(); - return 1 << (8 + interrupt->index); - } else { interrupt->risingTimestamp = hal::GetFPGATime(); return 1 << (interrupt->index); + } else { + interrupt->fallingTimestamp = hal::GetFPGATime(); + return 1 << (8 + interrupt->index); } } @@ -278,8 +280,8 @@ static int64_t WaitForInterruptAnalog(HAL_InterruptHandle handle, data->interruptHandle = handle; int32_t status = 0; - interrupt->previousState = GetAnalogTriggerValue( - interrupt->portHandle, interrupt->trigType, &status); + interrupt->currentState = GetAnalogTriggerValue(interrupt->portHandle, + interrupt->trigType, &status); if (status != 0) { return WaitResult::Timeout; @@ -322,14 +324,16 @@ static int64_t WaitForInterruptAnalog(HAL_InterruptHandle handle, if (timedOut) { return WaitResult::Timeout; } - // True => false, Falling - if (interrupt->previousState) { + // We know the value has changed because we would've timed out otherwise. + // If the current state is true, the previous state was false, so this is a + // rising edge. Otherwise, it's a falling edge. + if (interrupt->currentState) { // Set our return value and our timestamps - interrupt->fallingTimestamp = hal::GetFPGATime(); - return 1 << (8 + interrupt->index); - } else { interrupt->risingTimestamp = hal::GetFPGATime(); return 1 << (interrupt->index); + } else { + interrupt->fallingTimestamp = hal::GetFPGATime(); + return 1 << (8 + interrupt->index); } } diff --git a/wpilibc/src/test/native/cpp/InterruptTest.cpp b/wpilibc/src/test/native/cpp/InterruptTest.cpp index 96af18089fe..b21484c2c67 100644 --- a/wpilibc/src/test/native/cpp/InterruptTest.cpp +++ b/wpilibc/src/test/native/cpp/InterruptTest.cpp @@ -30,7 +30,7 @@ TEST(InterruptTest, AsynchronousInterrupt) { frc::Wait(0.5_s); DIOSim digitalSim{di}; digitalSim.SetValue(false); - frc::Wait(20_ms); + frc::Wait(10_ms); digitalSim.SetValue(true); frc::Wait(10_ms); @@ -42,4 +42,64 @@ TEST(InterruptTest, AsynchronousInterrupt) { } ASSERT_EQ(1, counter.load()); } + +TEST(InterruptTest, RisingEdge) { + HAL_Initialize(500, 0); + + std::atomic_bool hasFiredFallingEdge{false}; + std::atomic_bool hasFiredRisingEdge{false}; + + DigitalInput di{0}; + AsynchronousInterrupt interrupt{di, [&](bool rising, bool falling) { + hasFiredFallingEdge = falling; + hasFiredRisingEdge = rising; + }}; + interrupt.SetInterruptEdges(true, true); + DIOSim digitalSim{di}; + digitalSim.SetValue(false); + frc::Wait(0.5_s); + interrupt.Enable(); + frc::Wait(10_ms); + digitalSim.SetValue(true); + frc::Wait(10_ms); + + int count = 0; + while (!hasFiredRisingEdge) { + frc::Wait(5_ms); + count++; + ASSERT_TRUE(count < 1000); + } + EXPECT_FALSE(hasFiredFallingEdge); + EXPECT_TRUE(hasFiredRisingEdge); +} + +TEST(InterruptTest, FallingEdge) { + HAL_Initialize(500, 0); + + std::atomic_bool hasFiredFallingEdge{false}; + std::atomic_bool hasFiredRisingEdge{false}; + + DigitalInput di{0}; + AsynchronousInterrupt interrupt{di, [&](bool rising, bool falling) { + hasFiredFallingEdge = falling; + hasFiredRisingEdge = rising; + }}; + interrupt.SetInterruptEdges(true, true); + DIOSim digitalSim{di}; + digitalSim.SetValue(true); + frc::Wait(0.5_s); + interrupt.Enable(); + frc::Wait(10_ms); + digitalSim.SetValue(false); + frc::Wait(10_ms); + + int count = 0; + while (!hasFiredFallingEdge) { + frc::Wait(5_ms); + count++; + ASSERT_TRUE(count < 1000); + } + EXPECT_TRUE(hasFiredFallingEdge); + EXPECT_FALSE(hasFiredRisingEdge); +} } // namespace frc diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/InterruptTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/InterruptTest.java index bc32b8e3464..795f6291235 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/InterruptTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/InterruptTest.java @@ -4,7 +4,9 @@ package edu.wpi.first.wpilibj; +import static org.junit.jupiter.api.Assertions.assertAll; import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertTrue; import edu.wpi.first.wpilibj.simulation.DIOSim; @@ -22,7 +24,7 @@ void testAsynchronousInterrupt() { AsynchronousInterrupt interrupt = new AsynchronousInterrupt( di, - (a, b) -> { + (rising, falling) -> { counter.incrementAndGet(); hasFired.set(true); })) { @@ -43,4 +45,78 @@ void testAsynchronousInterrupt() { assertEquals(1, counter.get(), "The interrupt did not fire the expected number of times"); } } + + @Test + void testRisingEdge() { + AtomicBoolean hasFiredFallingEdge = new AtomicBoolean(false); + AtomicBoolean hasFiredRisingEdge = new AtomicBoolean(false); + + try (DigitalInput di = new DigitalInput(0); + AsynchronousInterrupt interrupt = + new AsynchronousInterrupt( + di, + (rising, falling) -> { + hasFiredFallingEdge.set(falling); + hasFiredRisingEdge.set(rising); + })) { + interrupt.setInterruptEdges(true, true); + DIOSim digitalSim = new DIOSim(di); + digitalSim.setValue(false); + Timer.delay(0.5); + interrupt.enable(); + Timer.delay(0.01); + digitalSim.setValue(true); + Timer.delay(0.01); + + int count = 0; + while (!hasFiredRisingEdge.get()) { + Timer.delay(0.005); + count++; + assertTrue(count < 1000); + } + assertAll( + () -> + assertFalse(hasFiredFallingEdge.get(), "The interrupt triggered on the falling edge"), + () -> + assertTrue( + hasFiredRisingEdge.get(), "The interrupt did not trigger on the rising edge")); + } + } + + @Test + void testFallingEdge() { + AtomicBoolean hasFiredFallingEdge = new AtomicBoolean(false); + AtomicBoolean hasFiredRisingEdge = new AtomicBoolean(false); + + try (DigitalInput di = new DigitalInput(0); + AsynchronousInterrupt interrupt = + new AsynchronousInterrupt( + di, + (rising, falling) -> { + hasFiredFallingEdge.set(falling); + hasFiredRisingEdge.set(rising); + })) { + interrupt.setInterruptEdges(true, true); + DIOSim digitalSim = new DIOSim(di); + digitalSim.setValue(true); + Timer.delay(0.5); + interrupt.enable(); + Timer.delay(0.01); + digitalSim.setValue(false); + Timer.delay(0.01); + + int count = 0; + while (!hasFiredFallingEdge.get()) { + Timer.delay(0.005); + count++; + assertTrue(count < 1000); + } + assertAll( + () -> + assertTrue( + hasFiredFallingEdge.get(), "The interrupt did not trigger on the rising edge"), + () -> + assertFalse(hasFiredRisingEdge.get(), "The interrupt triggered on the rising edge")); + } + } } From f62a055608b2b31cca548da096f27fb950cb2ef3 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 16 Jul 2024 20:20:22 -0700 Subject: [PATCH 08/10] [epilogue] Add missing docs (#6844) --- .../java/edu/wpi/first/epilogue/EpilogueConfiguration.java | 3 +++ .../main/java/edu/wpi/first/epilogue/logging/NullLogger.java | 3 +++ .../edu/wpi/first/epilogue/logging/errors/CrashOnError.java | 3 +++ .../edu/wpi/first/epilogue/logging/errors/ErrorPrinter.java | 3 +++ 4 files changed, 12 insertions(+) diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java index e5b569bf0ae..e9a9813023c 100644 --- a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java @@ -40,4 +40,7 @@ public class EpilogueConfiguration { * string. */ public String root = "Robot"; + + /** Default constructor. */ + public EpilogueConfiguration() {} } diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NullLogger.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NullLogger.java index fb6d30474b9..e5c973bfdac 100644 --- a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NullLogger.java +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/NullLogger.java @@ -8,6 +8,9 @@ /** Null data logger implementation that logs nothing. */ public class NullLogger implements DataLogger { + /** Default constructor. */ + public NullLogger() {} + @Override public DataLogger getSubLogger(String path) { // Since a sublogger would still log nothing and has no state, we can just return the same diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/CrashOnError.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/CrashOnError.java index 63a68d0852d..716695fd904 100644 --- a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/CrashOnError.java +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/CrashOnError.java @@ -12,6 +12,9 @@ * code. */ public class CrashOnError implements ErrorHandler { + /** Default constructor. */ + public CrashOnError() {} + @Override public void handle(Throwable exception, ClassSpecificLogger logger) { throw new RuntimeException( diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorPrinter.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorPrinter.java index 4987994f9ed..7baa6ffc09b 100644 --- a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorPrinter.java +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/logging/errors/ErrorPrinter.java @@ -8,6 +8,9 @@ /** An error handler implementation that prints error information to the console. */ public class ErrorPrinter implements ErrorHandler { + /** Default constructor. */ + public ErrorPrinter() {} + @Override public void handle(Throwable exception, ClassSpecificLogger logger) { System.err.println( From 57fa3887245d36d35cbd6827666fbc2b6c5cc959 Mon Sep 17 00:00:00 2001 From: Jade Date: Wed, 17 Jul 2024 11:22:39 +0800 Subject: [PATCH 09/10] [examples] Prepare for RobotInit deprecation by updating examples (#6623) Co-authored-by: Tyler Veness --- .../edu/wpi/first/vision/package-info.java | 13 +++++----- .../src/main/java/frc/robot/Robot.java | 3 +-- developerRobot/src/main/native/cpp/Robot.cpp | 3 ++- .../native/include/frc/IterativeRobotBase.h | 6 ++--- .../src/test/native/cpp/TimedRobotTest.cpp | 4 +-- .../cpp/examples/AddressableLED/cpp/Robot.cpp | 2 +- .../examples/AddressableLED/include/Robot.h | 2 +- .../examples/AprilTagsVision/cpp/Robot.cpp | 25 ++++++++++--------- .../cpp/examples/ArcadeDrive/cpp/Robot.cpp | 2 -- .../ArcadeDriveXboxController/cpp/Robot.cpp | 2 -- .../main/cpp/examples/ArmBot/cpp/Robot.cpp | 2 +- .../main/cpp/examples/ArmBot/include/Robot.h | 2 +- .../cpp/examples/ArmBotOffboard/cpp/Robot.cpp | 2 +- .../examples/ArmBotOffboard/include/Robot.h | 2 +- .../examples/ArmSimulation/include/Robot.h | 2 +- .../main/cpp/examples/CANPDP/cpp/Robot.cpp | 2 +- .../src/main/cpp/examples/DMA/cpp/Robot.cpp | 2 +- .../DriveDistanceOffboard/cpp/Robot.cpp | 2 +- .../DriveDistanceOffboard/include/Robot.h | 2 +- .../examples/DutyCycleEncoder/cpp/Robot.cpp | 2 +- .../cpp/examples/DutyCycleInput/cpp/Robot.cpp | 2 +- .../include/Robot.h | 2 +- .../ElevatorSimulation/include/Robot.h | 2 +- .../main/cpp/examples/EventLoop/cpp/Robot.cpp | 2 +- .../FlywheelBangBangController/cpp/Robot.cpp | 2 +- .../cpp/examples/Frisbeebot/cpp/Robot.cpp | 2 +- .../cpp/examples/Frisbeebot/include/Robot.h | 2 +- .../main/cpp/examples/GearsBot/cpp/Robot.cpp | 2 +- .../cpp/examples/GearsBot/include/Robot.h | 2 +- .../src/main/cpp/examples/Gyro/cpp/Robot.cpp | 8 +++--- .../examples/GyroDriveCommands/cpp/Robot.cpp | 2 +- .../GyroDriveCommands/include/Robot.h | 2 +- .../cpp/examples/GyroMecanum/cpp/Robot.cpp | 2 +- .../examples/HatchbotInlined/cpp/Robot.cpp | 2 +- .../examples/HatchbotInlined/include/Robot.h | 2 +- .../HatchbotTraditional/cpp/Robot.cpp | 2 +- .../HatchbotTraditional/include/Robot.h | 2 +- .../cpp/examples/HttpCamera/cpp/Robot.cpp | 15 +++++------ .../examples/IntermediateVision/cpp/Robot.cpp | 25 ++++++++++--------- .../MecanumControllerCommand/cpp/Robot.cpp | 2 +- .../MecanumControllerCommand/include/Robot.h | 2 +- .../cpp/examples/MecanumDrive/cpp/Robot.cpp | 2 +- .../cpp/examples/Mechanism2d/cpp/Robot.cpp | 2 +- .../cpp/examples/MotorControl/cpp/Robot.cpp | 2 +- .../cpp/examples/QuickVision/cpp/Robot.cpp | 4 +-- .../RapidReactCommandBot/cpp/Robot.cpp | 2 +- .../include/RapidReactCommandBot.h | 2 +- .../RapidReactCommandBot/include/Robot.h | 2 +- .../cpp/examples/RomiReference/cpp/Robot.cpp | 2 +- .../examples/RomiReference/include/Robot.h | 2 +- .../cpp/examples/SelectCommand/cpp/Robot.cpp | 2 +- .../examples/SelectCommand/include/Robot.h | 2 +- .../cpp/examples/ShuffleBoard/cpp/Robot.cpp | 2 +- .../cpp/Robot.cpp | 2 +- .../main/cpp/examples/Solenoid/cpp/Robot.cpp | 2 +- .../cpp/examples/Solenoid/include/Robot.h | 2 +- .../cpp/examples/StateSpaceArm/cpp/Robot.cpp | 2 +- .../examples/StateSpaceElevator/cpp/Robot.cpp | 2 +- .../examples/StateSpaceFlywheel/cpp/Robot.cpp | 2 +- .../StateSpaceFlywheelSysId/cpp/Robot.cpp | 2 +- .../SwerveControllerCommand/cpp/Robot.cpp | 2 +- .../SwerveControllerCommand/include/Robot.h | 2 +- .../src/main/cpp/examples/SysId/cpp/Robot.cpp | 2 +- .../main/cpp/examples/SysId/include/Robot.h | 2 +- .../main/cpp/examples/TankDrive/cpp/Robot.cpp | 2 +- .../TankDriveXboxController/cpp/Robot.cpp | 2 +- .../cpp/examples/Ultrasonic/cpp/Robot.cpp | 2 +- .../cpp/examples/Ultrasonic/include/Robot.h | 2 +- .../cpp/examples/XRPReference/cpp/Robot.cpp | 2 +- .../cpp/examples/XRPReference/include/Robot.h | 2 +- .../cpp/templates/commandbased/cpp/Robot.cpp | 2 +- .../templates/commandbased/include/Robot.h | 2 +- .../commandbasedskeleton/cpp/Robot.cpp | 2 +- .../commandbasedskeleton/include/Robot.h | 2 +- .../templates/robotbaseskeleton/cpp/Robot.cpp | 4 +-- .../robotbaseskeleton/include/Robot.h | 2 +- .../main/cpp/templates/timed/cpp/Robot.cpp | 2 +- .../main/cpp/templates/timed/include/Robot.h | 2 +- .../cpp/templates/timedskeleton/cpp/Robot.cpp | 2 +- .../templates/timedskeleton/include/Robot.h | 2 +- .../cpp/templates/timeslice/cpp/Robot.cpp | 2 -- .../cpp/templates/timeslice/include/Robot.h | 2 -- .../templates/timesliceskeleton/cpp/Robot.cpp | 1 - .../timesliceskeleton/include/Robot.h | 1 - .../wpi/first/wpilibj/IterativeRobotBase.java | 5 ++-- .../edu/wpi/first/wpilibj/TimedRobotTest.java | 3 --- .../examples/addressableled/Robot.java | 8 +++--- .../examples/apriltagsvision/Robot.java | 4 +-- .../wpilibj/examples/arcadedrive/Robot.java | 4 +-- .../arcadedrivexboxcontroller/Robot.java | 4 +-- .../first/wpilibj/examples/armbot/Robot.java | 5 ++-- .../examples/armbotoffboard/Robot.java | 5 ++-- .../wpilibj/examples/armsimulation/Robot.java | 3 +-- .../first/wpilibj/examples/canpdp/Robot.java | 3 +-- .../wpi/first/wpilibj/examples/dma/Robot.java | 14 +++++------ .../examples/drivedistanceoffboard/Robot.java | 5 ++-- .../examples/dutycycleencoder/Robot.java | 6 ++--- .../examples/dutycycleinput/Robot.java | 5 ++-- .../elevatorexponentialprofile/Robot.java | 3 +-- .../elevatorexponentialsimulation/Robot.java | 3 --- .../examples/elevatorprofiledpid/Robot.java | 3 +-- .../examples/elevatorsimulation/Robot.java | 3 +-- .../elevatortrapezoidprofile/Robot.java | 3 +-- .../first/wpilibj/examples/encoder/Robot.java | 4 +-- .../wpilibj/examples/eventloop/Robot.java | 4 +-- .../flywheelbangbangcontroller/Robot.java | 3 +-- .../wpilibj/examples/frisbeebot/Robot.java | 5 ++-- .../wpilibj/examples/gearsbot/Robot.java | 5 ++-- .../examples/gettingstarted/Robot.java | 8 +----- .../first/wpilibj/examples/gyro/Robot.java | 4 +-- .../examples/gyrodrivecommands/Robot.java | 5 ++-- .../wpilibj/examples/gyromecanum/Robot.java | 16 ++++++------ .../examples/hatchbotinlined/Robot.java | 5 ++-- .../examples/hatchbottraditional/Robot.java | 5 ++-- .../wpilibj/examples/httpcamera/Robot.java | 4 +-- .../examples/intermediatevision/Robot.java | 4 +-- .../mecanumcontrollercommand/Robot.java | 5 ++-- .../wpilibj/examples/mecanumdrive/Robot.java | 18 ++++++------- .../wpilibj/examples/mechanism2d/Robot.java | 8 +++--- .../wpilibj/examples/motorcontrol/Robot.java | 11 ++++---- .../wpilibj/examples/quickvision/Robot.java | 5 ++-- .../RapidReactCommandBot.java | 2 +- .../examples/rapidreactcommandbot/Robot.java | 3 +-- .../wpilibj/examples/romireference/Robot.java | 5 ++-- .../wpilibj/examples/selectcommand/Robot.java | 5 ++-- .../wpilibj/examples/shuffleboard/Robot.java | 6 ++--- .../Robot.java | 6 ++--- .../wpilibj/examples/solenoid/Robot.java | 4 +-- .../wpilibj/examples/statespacearm/Robot.java | 3 +-- .../examples/statespaceelevator/Robot.java | 3 +-- .../examples/statespaceflywheel/Robot.java | 3 +-- .../statespaceflywheelsysid/Robot.java | 3 +-- .../swervecontrollercommand/Robot.java | 5 ++-- .../first/wpilibj/examples/sysid/Robot.java | 3 +-- .../examples/sysid/SysIdRoutineBot.java | 2 +- .../wpilibj/examples/tankdrive/Robot.java | 16 ++++++------ .../tankdrivexboxcontroller/Robot.java | 4 +-- .../wpilibj/examples/ultrasonic/Robot.java | 4 +-- .../wpilibj/examples/xrpreference/Robot.java | 5 ++-- .../wpilibj/templates/commandbased/Robot.java | 5 ++-- .../templates/commandbasedskeleton/Robot.java | 5 ++-- .../educational/EducationalRobot.java | 4 +-- .../wpilibj/templates/educational/Robot.java | 3 +-- .../templates/robotbaseskeleton/Robot.java | 4 +-- .../templates/romicommandbased/Robot.java | 5 ++-- .../romieducational/EducationalRobot.java | 4 +-- .../templates/romieducational/Robot.java | 3 +-- .../wpilibj/templates/romitimed/Robot.java | 3 +-- .../first/wpilibj/templates/timed/Robot.java | 3 +-- .../templates/timedskeleton/Robot.java | 3 +-- .../wpilibj/templates/timeslice/Robot.java | 7 ------ .../templates/timesliceskeleton/Robot.java | 7 ------ .../templates/xrpcommandbased/Robot.java | 5 ++-- .../xrpeducational/EducationalRobot.java | 4 +-- .../templates/xrpeducational/Robot.java | 3 +-- .../wpilibj/templates/xrptimed/Robot.java | 3 +-- 156 files changed, 260 insertions(+), 355 deletions(-) diff --git a/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java b/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java index e4515cbb0e5..d666206c320 100644 --- a/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java +++ b/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java @@ -30,6 +30,12 @@ * private double angleToTote = 0; * private double distanceToTote = 0; * + * public Robot() { + * usbCamera = CameraServer.startAutomaticCapture(0); + * findTotePipeline = new MyFindTotePipeline(); + * findToteThread = new VisionThread(usbCamera, findTotePipeline, this); + * } + * * {@literal @}Override * public void {@link edu.wpi.first.vision.VisionRunner.Listener#copyPipelineOutputs * copyPipelineOutputs(MyFindTotePipeline pipeline)} { @@ -43,13 +49,6 @@ * } * * {@literal @}Override - * public void robotInit() { - * usbCamera = CameraServer.startAutomaticCapture(0); - * findTotePipeline = new MyFindTotePipeline(); - * findToteThread = new VisionThread(usbCamera, findTotePipeline, this); - * } - * - * {@literal @}Override * public void autonomousInit() { * findToteThread.start(); * } diff --git a/developerRobot/src/main/java/frc/robot/Robot.java b/developerRobot/src/main/java/frc/robot/Robot.java index 0263e336983..6cf3f4738d7 100644 --- a/developerRobot/src/main/java/frc/robot/Robot.java +++ b/developerRobot/src/main/java/frc/robot/Robot.java @@ -11,8 +11,7 @@ public class Robot extends TimedRobot { * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() {} + public Robot() {} /** This function is run once each time the robot enters autonomous mode. */ @Override diff --git a/developerRobot/src/main/native/cpp/Robot.cpp b/developerRobot/src/main/native/cpp/Robot.cpp index 238697d42bd..6e013599e17 100644 --- a/developerRobot/src/main/native/cpp/Robot.cpp +++ b/developerRobot/src/main/native/cpp/Robot.cpp @@ -5,11 +5,12 @@ #include class Robot : public frc::TimedRobot { + public: /** * This function is run when the robot is first started up and should be * used for any initialization code. */ - void RobotInit() override {} + Robot() {} /** * This function is run once each time the robot enters autonomous mode diff --git a/wpilibc/src/main/native/include/frc/IterativeRobotBase.h b/wpilibc/src/main/native/include/frc/IterativeRobotBase.h index 8329c0b10e7..d730c70c4af 100644 --- a/wpilibc/src/main/native/include/frc/IterativeRobotBase.h +++ b/wpilibc/src/main/native/include/frc/IterativeRobotBase.h @@ -63,10 +63,8 @@ class IterativeRobotBase : public RobotBase { * which will be called when the robot is first powered on. It will be called * exactly one time. * - * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready" - * indicators will be off until RobotInit() exits. Code in RobotInit() that - * waits for enable will cause the robot to never indicate that the code is - * ready, causing the robot to be bypassed in a match. + * Note: This method is functionally identical to the class constructor so + * that should be used instead. */ virtual void RobotInit(); diff --git a/wpilibc/src/test/native/cpp/TimedRobotTest.cpp b/wpilibc/src/test/native/cpp/TimedRobotTest.cpp index 78d18b5b3cc..d639ecce078 100644 --- a/wpilibc/src/test/native/cpp/TimedRobotTest.cpp +++ b/wpilibc/src/test/native/cpp/TimedRobotTest.cpp @@ -48,9 +48,7 @@ class MockRobot : public TimedRobot { std::atomic m_teleopPeriodicCount{0}; std::atomic m_testPeriodicCount{0}; - MockRobot() : TimedRobot{kPeriod} {} - - void RobotInit() override { m_robotInitCount++; } + MockRobot() : TimedRobot{kPeriod} { m_robotInitCount++; } void SimulationInit() override { m_simulationInitCount++; } diff --git a/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp index 97c0925e4ff..70808ab4739 100644 --- a/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp @@ -4,7 +4,7 @@ #include "Robot.h" -void Robot::RobotInit() { +Robot::Robot() { // Default to a length of 60, start empty output // Length is expensive to set, so only set it once, then just update data m_led.SetLength(kLength); diff --git a/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.h index 488f5e5991c..9f87d160605 100644 --- a/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.h @@ -12,7 +12,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; private: diff --git a/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp index 9f23be34075..b5df25d5973 100644 --- a/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp @@ -32,6 +32,19 @@ * solution! */ class Robot : public frc::TimedRobot { + public: + Robot() { + // We need to run our vision program in a separate thread. If not, our robot + // program will not run. +#if defined(__linux__) || defined(_WIN32) + std::thread visionThread(VisionThread); + visionThread.detach(); +#else + std::fputs("Vision only available on Linux or Windows.\n", stderr); + std::fflush(stderr); +#endif + } + #if defined(__linux__) || defined(_WIN32) private: @@ -147,18 +160,6 @@ class Robot : public frc::TimedRobot { } } #endif - - void RobotInit() override { - // We need to run our vision program in a separate thread. If not, our robot - // program will not run. -#if defined(__linux__) || defined(_WIN32) - std::thread visionThread(VisionThread); - visionThread.detach(); -#else - std::fputs("Vision only available on Linux or Windows.\n", stderr); - std::fflush(stderr); -#endif - } }; #ifndef RUNNING_FRC_TESTS diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp index 9c8d64064fa..1c3e3564d3d 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp @@ -23,9 +23,7 @@ class Robot : public frc::TimedRobot { Robot() { wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); - } - void RobotInit() override { // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp index 38ff862ab96..416c49c0f18 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp @@ -23,9 +23,7 @@ class Robot : public frc::TimedRobot { Robot() { wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); - } - void RobotInit() override { // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp index 13eb9f9ac46..66f1a891db6 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Robot.h index de9c814e752..24056944479 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Robot.h @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp index c4c1661d699..142d59fa6be 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Robot.h index de9c814e752..24056944479 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Robot.h @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Robot.h index fdcb5ce7f9a..30d90b6ca58 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Robot.h @@ -14,7 +14,7 @@ */ class Robot : public frc::TimedRobot { public: - void RobotInit() override {} + Robot() {} void SimulationPeriodic() override; void TeleopInit() override; void TeleopPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp index 95a9a0d4121..b22c27cf904 100644 --- a/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp @@ -13,7 +13,7 @@ */ class Robot : public frc::TimedRobot { public: - void RobotInit() override { + Robot() { // Put the PDP itself to the dashboard frc::SmartDashboard::PutData("PDP", &m_pdp); } diff --git a/wpilibcExamples/src/main/cpp/examples/DMA/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DMA/cpp/Robot.cpp index 9097d944568..e5f47278731 100644 --- a/wpilibcExamples/src/main/cpp/examples/DMA/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DMA/cpp/Robot.cpp @@ -25,7 +25,7 @@ class Robot : public frc::TimedRobot { frc::Encoder m_encoder{0, 1}; public: - void RobotInit() override { + Robot() { // Trigger on falling edge of dma trigger output m_dma.SetExternalTrigger(&m_dmaTrigger, false, true); diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp index c4c1661d699..142d59fa6be 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.h index de9c814e752..24056944479 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.h @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp index 3889d1c4dad..9d506f64fcf 100644 --- a/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp @@ -20,7 +20,7 @@ class Robot : public frc::TimedRobot { frc::DutyCycleEncoder m_dutyCycleEncoder{0, fullRange, expectedZero}; public: - void RobotInit() override { + Robot() { // If you know the frequency of your sensor, uncomment the following // method, and set the method to the frequency of your sensor. // This will result in more stable readings from the sensor. diff --git a/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp index 69d41bcfbcb..7be548d7447 100644 --- a/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp @@ -12,7 +12,7 @@ class Robot : public frc::TimedRobot { frc::DutyCycle m_dutyCycle{m_input}; // Duty cycle input public: - void RobotInit() override {} + Robot() {} void RobotPeriodic() override { // Duty Cycle Frequency in Hz diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Robot.h index f10310483d7..4e650b2fb9b 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Robot.h @@ -14,7 +14,7 @@ */ class Robot : public frc::TimedRobot { public: - void RobotInit() override {} + Robot() {} void RobotPeriodic() override; void SimulationPeriodic() override; void TeleopInit() override; diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Robot.h index 53f50eabfea..70ff4fae031 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Robot.h @@ -14,7 +14,7 @@ */ class Robot : public frc::TimedRobot { public: - void RobotInit() override {} + Robot() {} void RobotPeriodic() override; void SimulationPeriodic() override; void TeleopPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp index a29d1699528..baab35f888d 100644 --- a/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp @@ -22,7 +22,7 @@ static const auto KICKER_THRESHOLD = 15_mm; class Robot : public frc::TimedRobot { public: - void RobotInit() override { + Robot() { m_controller.SetTolerance(TOLERANCE.value()); frc::BooleanEvent isBallAtKicker{&m_loop, [&kickerSensor = m_kickerSensor] { diff --git a/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp index 6763e7f97c2..88e552198a5 100644 --- a/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp @@ -40,7 +40,7 @@ class Robot : public frc::TimedRobot { 0.9 * m_feedforward.Calculate(setpoint)); } - void RobotInit() override { + Robot() { // Add bang-bang controler to SmartDashboard and networktables. frc::SmartDashboard::PutData("BangBangControler", &m_bangBangControler); } diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/Robot.cpp index c7eab485a5d..580decec83e 100644 --- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Robot.h index a82f2ac63b0..b670df4cd8b 100644 --- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Robot.h @@ -11,7 +11,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp index c7eab485a5d..580decec83e 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/Robot.h index a82f2ac63b0..b670df4cd8b 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/Robot.h @@ -11,7 +11,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp index d8af4100acb..5aee5916f9f 100644 --- a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp @@ -18,16 +18,14 @@ class Robot : public frc::TimedRobot { public: Robot() { - wpi::SendableRegistry::AddChild(&m_drive, &m_left); - wpi::SendableRegistry::AddChild(&m_drive, &m_right); - } - - void RobotInit() override { m_gyro.SetSensitivity(kVoltsPerDegreePerSecond); // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. m_right.SetInverted(true); + + wpi::SendableRegistry::AddChild(&m_drive, &m_left); + wpi::SendableRegistry::AddChild(&m_drive, &m_right); } /** diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp index c4c1661d699..142d59fa6be 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Robot.h index de9c814e752..24056944479 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Robot.h @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp index 7c589fd268e..e9ee85c8fff 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp @@ -15,7 +15,7 @@ */ class Robot : public frc::TimedRobot { public: - void RobotInit() override { + Robot() { wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft); wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft); wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp index 72efd400492..d731edc1c90 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp @@ -9,7 +9,7 @@ #include #include -void Robot::RobotInit() { +Robot::Robot() { // Start recording to data log frc::DataLogManager::Start(); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.h index a82f2ac63b0..b670df4cd8b 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.h @@ -11,7 +11,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp index 72efd400492..d731edc1c90 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp @@ -9,7 +9,7 @@ #include #include -void Robot::RobotInit() { +Robot::Robot() { // Start recording to data log frc::DataLogManager::Start(); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.h index a82f2ac63b0..b670df4cd8b 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.h @@ -11,7 +11,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp index e8b5fe0aa24..327569ddfb0 100644 --- a/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp @@ -15,6 +15,14 @@ * processing. */ class Robot : public frc::TimedRobot { + public: + Robot() { + // We need to run our vision program in a separate thread. If not, our robot + // program will not run. + std::thread visionThread(VisionThread); + visionThread.detach(); + } + private: static void VisionThread() { // Create an HTTP camera. The address will need to be modified to have the @@ -50,13 +58,6 @@ class Robot : public frc::TimedRobot { outputStream.PutFrame(mat); } } - - void RobotInit() override { - // We need to run our vision program in a separate thread. If not, our robot - // program will not run. - std::thread visionThread(VisionThread); - visionThread.detach(); - } }; #ifndef RUNNING_FRC_TESTS diff --git a/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp index b61f86d56b9..a65646c3d1f 100644 --- a/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp @@ -18,6 +18,19 @@ * processing. */ class Robot : public frc::TimedRobot { + public: + Robot() { + // We need to run our vision program in a separate thread. If not, our robot + // program will not run. +#if defined(__linux__) || defined(_WIN32) + std::thread visionThread(VisionThread); + visionThread.detach(); +#else + std::fputs("Vision only available on Linux or Windows.\n", stderr); + std::fflush(stderr); +#endif + } + #if defined(__linux__) || defined(_WIN32) private: @@ -55,18 +68,6 @@ class Robot : public frc::TimedRobot { } } #endif - - void RobotInit() override { - // We need to run our vision program in a separate thread. If not, our robot - // program will not run. -#if defined(__linux__) || defined(_WIN32) - std::thread visionThread(VisionThread); - visionThread.detach(); -#else - std::fputs("Vision only available on Linux or Windows.\n", stderr); - std::fflush(stderr); -#endif - } }; #ifndef RUNNING_FRC_TESTS diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp index c4c1661d699..142d59fa6be 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Robot.h index de9c814e752..24056944479 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Robot.h @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp index eeb9ce13233..84cbf7916b6 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp @@ -13,7 +13,7 @@ */ class Robot : public frc::TimedRobot { public: - void RobotInit() override { + Robot() { wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft); wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft); wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight); diff --git a/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp index 6d1967fd29f..600f28b3414 100644 --- a/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp @@ -30,7 +30,7 @@ class Robot : public frc::TimedRobot { static constexpr double kElevatorMinimumLength = 0.5; public: - void RobotInit() override { + Robot() { m_elevatorEncoder.SetDistancePerPulse(kMetersPerPulse); // publish to dashboard diff --git a/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp index 7a4325f3714..f3b114edc72 100644 --- a/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp @@ -33,7 +33,7 @@ class Robot : public frc::TimedRobot { frc::SmartDashboard::PutNumber("Encoder", m_encoder.GetDistance()); } - void RobotInit() override { + Robot() { // Use SetDistancePerPulse to set the multiplier for GetDistance // This is set up assuming a 6 inch wheel with a 360 CPR encoder. m_encoder.SetDistancePerPulse((std::numbers::pi * 6) / 360.0); diff --git a/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp index aae646f8db3..3044e82352e 100644 --- a/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp @@ -11,11 +11,11 @@ * Uses the CameraServer class to automatically capture video from a USB webcam * and send it to the FRC dashboard without doing any vision processing. This is * the easiest way to get camera images to the dashboard. Just add this to the - * RobotInit() method in your program. + * robot class constructor. */ class Robot : public frc::TimedRobot { public: - void RobotInit() override { + Robot() { #if defined(__linux__) || defined(_WIN32) frc::CameraServer::StartAutomaticCapture(); #else diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp index 06bbe40c9a3..d28c275f8ef 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp @@ -4,7 +4,7 @@ #include "Robot.h" -void Robot::RobotInit() { +Robot::Robot() { // Configure default commands and condition bindings on robot startup m_robot.ConfigureBindings(); } diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.h b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.h index 0071a83b65d..77f8340e6dc 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.h +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.h @@ -27,7 +27,7 @@ class RapidReactCommandBot { * Use this method to define bindings between conditions and commands. These * are useful for automating robot behaviors based on button and sensor input. * - *

Should be called during Robot::RobotInit(). + *

Should be called in the robot class constructor. * *

Event binding methods are available on the frc2::Trigger class. */ diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.h index bab80f7039c..e88daeecef9 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.h @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp index e39a8fd5811..59163407357 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp @@ -6,7 +6,7 @@ #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.h index eb35fab06dd..f6b09dcc2f3 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.h @@ -11,7 +11,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp index c7eab485a5d..580decec83e 100644 --- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Robot.h index a82f2ac63b0..b670df4cd8b 100644 --- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Robot.h @@ -11,7 +11,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp index b532bcbf75b..61c5dd44964 100644 --- a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp @@ -29,7 +29,7 @@ */ class Robot : public frc::TimedRobot { public: - void RobotInit() override { + Robot() { wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left); wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right); diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp index fa1cfe1bdb9..8b31c3dd3dd 100644 --- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override { + Robot() { m_trajectory = frc::TrajectoryGenerator::GenerateTrajectory( frc::Pose2d{2_m, 2_m, 0_rad}, {}, frc::Pose2d{6_m, 4_m, 0_rad}, frc::TrajectoryConfig(2_mps, 2_mps_sq)); diff --git a/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp index 88a2dbf242e..25311e82d68 100644 --- a/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() { +Robot::Robot() { // Publish elements to shuffleboard. frc::ShuffleboardTab& tab = frc::Shuffleboard::GetTab("Pneumatics"); tab.Add("Single Solenoid", m_solenoid); diff --git a/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.h index 550e949994c..46920ce620f 100644 --- a/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.h @@ -35,7 +35,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void TeleopPeriodic() override; private: diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp index 01d3db6abe3..8233e7cde89 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp @@ -93,7 +93,7 @@ class Robot : public frc::TimedRobot { frc::TrapezoidProfile::State m_lastProfiledReference; public: - void RobotInit() override { + Robot() { // We go 2 pi radians per 4096 clicks. m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0); } diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp index 08074f8cf1b..7c8a4613074 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp @@ -92,7 +92,7 @@ class Robot : public frc::TimedRobot { frc::TrapezoidProfile::State m_lastProfiledReference; public: - void RobotInit() override { + Robot() { // Circumference = pi * d, so distance per click = pi * d / counts m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi * kDrumRadius.value() / 4096.0); diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp index b0a9ed3a92f..4e3b7cdd160 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp @@ -80,7 +80,7 @@ class Robot : public frc::TimedRobot { frc::XboxController m_joystick{kJoystickPort}; public: - void RobotInit() override { + Robot() { // We go 2 pi radians per 4096 clicks. m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0); } diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp index 2be14fd49f0..8546f7c0444 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp @@ -80,7 +80,7 @@ class Robot : public frc::TimedRobot { frc::XboxController m_joystick{kJoystickPort}; public: - void RobotInit() override { + Robot() { // We go 2 pi radians per 4096 clicks. m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0); } diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp index c4c1661d699..142d59fa6be 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Robot.h index de9c814e752..24056944479 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Robot.h @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SysId/cpp/Robot.cpp index 32782b29ae2..2ed3f804f55 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysId/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SysId/cpp/Robot.cpp @@ -6,7 +6,7 @@ #include -void Robot::RobotInit() {} +Robot::Robot() {} void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/SysId/include/Robot.h index b6142c2405b..c6e5806d9a8 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysId/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/SysId/include/Robot.h @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp index f7b3e9c6900..91a21979268 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp @@ -21,7 +21,7 @@ class Robot : public frc::TimedRobot { frc::Joystick m_rightStick{1}; public: - void RobotInit() override { + Robot() { wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); diff --git a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp index 7c0706ef791..6241d3c396e 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp @@ -20,7 +20,7 @@ class Robot : public frc::TimedRobot { frc::XboxController m_driverController{0}; public: - void RobotInit() override { + Robot() { wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); diff --git a/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp index ac47856ee2e..67c5b719b01 100644 --- a/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp @@ -8,7 +8,7 @@ #include #include -void Robot::RobotInit() { +Robot::Robot() { // Add the ultrasonic on the "Sensors" tab of the dashboard // Data will update automatically frc::Shuffleboard::GetTab("Sensors").Add(m_rangeFinder); diff --git a/wpilibcExamples/src/main/cpp/examples/Ultrasonic/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/Ultrasonic/include/Robot.h index 2da0c6ffa5e..9d14ae0ef8b 100644 --- a/wpilibcExamples/src/main/cpp/examples/Ultrasonic/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/Ultrasonic/include/Robot.h @@ -13,7 +13,7 @@ */ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void TeleopPeriodic() override; void TestInit() override; void TestPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp index e39a8fd5811..59163407357 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp @@ -6,7 +6,7 @@ #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.h index eb35fab06dd..f6b09dcc2f3 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.h @@ -11,7 +11,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp index c1c1ae64437..6a1eb4beea5 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp @@ -6,7 +6,7 @@ #include -void Robot::RobotInit() {} +Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h index e9d45e7acdd..794e6437a93 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp index 32782b29ae2..2ed3f804f55 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp @@ -6,7 +6,7 @@ #include -void Robot::RobotInit() {} +Robot::Robot() {} void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); diff --git a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.h index 6bdb217a2a5..886f9b9fc49 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.h @@ -13,7 +13,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp index 0c67d6d7f04..850e2e41800 100644 --- a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp @@ -11,7 +11,7 @@ #include #include -void Robot::RobotInit() {} +Robot::Robot() {} void Robot::Disabled() {} @@ -22,8 +22,6 @@ void Robot::Teleop() {} void Robot::Test() {} void Robot::StartCompetition() { - RobotInit(); - frc::internal::DriverStationModeThread modeThread; wpi::Event event{false, false}; diff --git a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.h index 9b63fb26d77..cb165d0524a 100644 --- a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.h @@ -10,7 +10,7 @@ class Robot : public frc::RobotBase { public: - void RobotInit(); + Robot(); void Disabled(); void Autonomous(); void Teleop(); diff --git a/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp index c248d043593..162037e3e49 100644 --- a/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -void Robot::RobotInit() { +Robot::Robot() { m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault); m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom); frc::SmartDashboard::PutData("Auto Modes", &m_chooser); diff --git a/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h index 5677a88fe52..cdf36b8508e 100644 --- a/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h @@ -11,7 +11,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void AutonomousInit() override; void AutonomousPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp index d5b57c2836a..85a862f5f17 100644 --- a/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp @@ -4,7 +4,7 @@ #include "Robot.h" -void Robot::RobotInit() {} +Robot::Robot() {} void Robot::RobotPeriodic() {} void Robot::AutonomousInit() {} diff --git a/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h index 062a198f168..8d87e6b5c0f 100644 --- a/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h @@ -8,7 +8,7 @@ class Robot : public frc::TimedRobot { public: - void RobotInit() override; + Robot(); void RobotPeriodic() override; void AutonomousInit() override; diff --git a/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp index 3dec6eb3657..7f79b234965 100644 --- a/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp @@ -23,9 +23,7 @@ Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} { // Total usage: // 5 ms (robot) + 2 ms (controller 1) + 2 ms (controller 2) = 9 ms // 9 ms / 10 ms -> 90% allocated -} -void Robot::RobotInit() { m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault); m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom); frc::SmartDashboard::PutData("Auto Modes", &m_chooser); diff --git a/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.h index aaafdf7df19..82e0ceba0bf 100644 --- a/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.h @@ -12,8 +12,6 @@ class Robot : public frc::TimesliceRobot { public: Robot(); - - void RobotInit() override; void RobotPeriodic() override; void AutonomousInit() override; void AutonomousPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp index 10f98dd5656..1a4f064affb 100644 --- a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp @@ -23,7 +23,6 @@ Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} { // 9 ms / 10 ms -> 90% allocated } -void Robot::RobotInit() {} void Robot::RobotPeriodic() {} void Robot::AutonomousInit() {} diff --git a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.h index 6659bf99c6c..d599e413fe1 100644 --- a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.h @@ -10,7 +10,6 @@ class Robot : public frc::TimesliceRobot { public: Robot(); - void RobotInit() override; void RobotPeriodic() override; void AutonomousInit() override; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java index e7869544704..50eddff5fdb 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java @@ -97,9 +97,8 @@ protected IterativeRobotBase(double period) { *

Users should override this method for default Robot-wide initialization which will be called * when the robot is first powered on. It will be called exactly one time. * - *

Warning: the Driver Station "Robot Code" light and FMS "Robot Ready" indicators will be off - * until RobotInit() exits. Code in RobotInit() that waits for enable will cause the robot to - * never indicate that the code is ready, causing the robot to be bypassed in a match. + *

Note: This method is functionally identical to the class constructor so that should be used + * instead. */ public void robotInit() {} diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java index 920fb546e8c..da0bd92bdb3 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java @@ -45,10 +45,7 @@ static class MockRobot extends TimedRobot { MockRobot() { super(kPeriod); - } - @Override - public void robotInit() { m_robotInitCount.addAndGet(1); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/addressableled/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/addressableled/Robot.java index 3c5b2f7eb07..16e5321307a 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/addressableled/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/addressableled/Robot.java @@ -15,8 +15,8 @@ import edu.wpi.first.wpilibj.TimedRobot; public class Robot extends TimedRobot { - private AddressableLED m_led; - private AddressableLEDBuffer m_ledBuffer; + private final AddressableLED m_led; + private final AddressableLEDBuffer m_ledBuffer; // Create an LED pattern that will display a rainbow across // all hues at maximum saturation and half brightness @@ -30,8 +30,8 @@ public class Robot extends TimedRobot { private final LEDPattern m_scrollingRainbow = m_rainbow.scrollAtAbsoluteSpeed(MetersPerSecond.of(1), kLedSpacing); - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { // PWM port 9 // Must be a PWM header, not MXP or DIO m_led = new AddressableLED(9); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/apriltagsvision/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/apriltagsvision/Robot.java index 8609cf7e47c..fa827d9afe0 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/apriltagsvision/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/apriltagsvision/Robot.java @@ -30,8 +30,8 @@ *

Be aware that the performance on this is much worse than a coprocessor solution! */ public class Robot extends TimedRobot { - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { var visionThread = new Thread(this::apriltagVisionThreadProc); visionThread.setDaemon(true); visionThread.start(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java index aa343799a01..43fca7a0bc6 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java @@ -21,13 +21,11 @@ public class Robot extends TimedRobot { new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final Joystick m_stick = new Joystick(0); + /** Called once at the beginning of the robot program. */ public Robot() { SendableRegistry.addChild(m_robotDrive, m_leftMotor); SendableRegistry.addChild(m_robotDrive, m_rightMotor); - } - @Override - public void robotInit() { // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java index a376fe0ae48..f4a99c7fb8d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java @@ -21,13 +21,11 @@ public class Robot extends TimedRobot { new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final XboxController m_driverController = new XboxController(0); + /** Called once at the beginning of the robot program. */ public Robot() { SendableRegistry.addChild(m_robotDrive, m_leftMotor); SendableRegistry.addChild(m_robotDrive, m_rightMotor); - } - @Override - public void robotInit() { // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Robot.java index c2dc4fcd27c..77edb064a46 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Robot.java index 160146c9426..84601c339ed 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/Robot.java index 80a11215cd5..761e37b2e14 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/Robot.java @@ -13,8 +13,7 @@ public class Robot extends TimedRobot { private final Arm m_arm = new Arm(); private final Joystick m_joystick = new Joystick(Constants.kJoystickPort); - @Override - public void robotInit() {} + public Robot() {} @Override public void simulationPeriodic() { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java index e2b699d2509..796bf0f76e2 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java @@ -15,8 +15,7 @@ public class Robot extends TimedRobot { private final PowerDistribution m_pdp = new PowerDistribution(); - @Override - public void robotInit() { + public Robot() { // Put the PDP itself to the dashboard SmartDashboard.putData("PDP", m_pdp); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dma/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dma/Robot.java index a7b088c735d..fb918ff15e6 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dma/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dma/Robot.java @@ -15,22 +15,22 @@ /** This is a sample program showing how to to use DMA to read a sensor. */ public class Robot extends TimedRobot { - private DMA m_dma; - private DMASample m_dmaSample; + private final DMA m_dma; + private final DMASample m_dmaSample; // DMA needs a trigger, can use an output as trigger. // 8 Triggers exist per DMA object, can be triggered on any // DigitalSource. - private DigitalOutput m_dmaTrigger; + private final DigitalOutput m_dmaTrigger; // Analog input to read with DMA - private AnalogInput m_analogInput; + private final AnalogInput m_analogInput; // Encoder to read with DMA - private Encoder m_encoder; + private final Encoder m_encoder; - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { m_dma = new DMA(); m_dmaSample = new DMASample(); m_dmaTrigger = new DigitalOutput(2); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Robot.java index 4316ad3bdee..7102dac0862 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java index c3015058281..e352e84076e 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java @@ -11,12 +11,12 @@ /** This example shows how to use a duty cycle encoder for devices such as an arm or elevator. */ public class Robot extends TimedRobot { - private DutyCycleEncoder m_dutyCycleEncoder; + private final DutyCycleEncoder m_dutyCycleEncoder; private static final double m_fullRange = 1.3; private static final double m_expectedZero = 0; - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { // 2nd parameter is the range of values. This sensor will output between // 0 and the passed in value. // 3rd parameter is the the physical value where you want "0" to be. How diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java index c7350b089ba..ca45d031356 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java @@ -10,10 +10,9 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; public class Robot extends TimedRobot { - private DutyCycle m_dutyCycle; + private final DutyCycle m_dutyCycle; - @Override - public void robotInit() { + public Robot() { m_dutyCycle = new DutyCycle(new DigitalInput(0)); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/Robot.java index 1bd9c727c43..83958230ec6 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/Robot.java @@ -27,8 +27,7 @@ public class Robot extends TimedRobot { private ExponentialProfile.State m_goal = new ExponentialProfile.State(0, 0); private ExponentialProfile.State m_setpoint = new ExponentialProfile.State(0, 0); - @Override - public void robotInit() { + public Robot() { // Note: These gains are fake, and will have to be tuned for your robot. m_motor.setPID(1.3, 0.0, 0.7); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Robot.java index a123414e36a..889fe8e9b32 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Robot.java @@ -17,9 +17,6 @@ public Robot() { super(0.020); } - @Override - public void robotInit() {} - @Override public void robotPeriodic() { // Update the telemetry, including mechanism visualization, regardless of mode. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorprofiledpid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorprofiledpid/Robot.java index 670fd7b8ee9..ee37915d67a 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorprofiledpid/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorprofiledpid/Robot.java @@ -36,8 +36,7 @@ public class Robot extends TimedRobot { new ProfiledPIDController(kP, kI, kD, m_constraints, kDt); private final ElevatorFeedforward m_feedforward = new ElevatorFeedforward(kS, kG, kV); - @Override - public void robotInit() { + public Robot() { m_encoder.setDistancePerPulse(1.0 / 360.0 * 2.0 * Math.PI * 1.5); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java index de39b88a60a..e45ba060918 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java @@ -13,8 +13,7 @@ public class Robot extends TimedRobot { private final Joystick m_joystick = new Joystick(Constants.kJoystickPort); private final Elevator m_elevator = new Elevator(); - @Override - public void robotInit() {} + public Robot() {} @Override public void robotPeriodic() { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java index d451c1377fe..e1ae800421d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java @@ -27,8 +27,7 @@ public class Robot extends TimedRobot { private TrapezoidProfile.State m_goal = new TrapezoidProfile.State(); private TrapezoidProfile.State m_setpoint = new TrapezoidProfile.State(); - @Override - public void robotInit() { + public Robot() { // Note: These gains are fake, and will have to be tuned for your robot. m_motor.setPID(1.3, 0.0, 0.7); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/encoder/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/encoder/Robot.java index 3b715eb8e15..68837135b34 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/encoder/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/encoder/Robot.java @@ -34,8 +34,8 @@ public class Robot extends TimedRobot { */ private final Encoder m_encoder = new Encoder(1, 2, false, CounterBase.EncodingType.k4X); - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { /* * Defines the number of samples to average when determining the rate. * On a quadrature encoder, values range from 1-255; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java index 63efa633519..e75edfe3d19 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java @@ -35,8 +35,8 @@ public class Robot extends TimedRobot { private final EventLoop m_loop = new EventLoop(); private final Joystick m_joystick = new Joystick(0); - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { m_controller.setTolerance(TOLERANCE); BooleanEvent isBallAtKicker = diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java index e4732131875..b62c90077af 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java @@ -68,8 +68,7 @@ public class Robot extends TimedRobot { private final FlywheelSim m_flywheelSim = new FlywheelSim(m_plant, m_gearbox); private final EncoderSim m_encoderSim = new EncoderSim(m_encoder); - @Override - public void robotInit() { + public Robot() { // Add bang-bang controler to SmartDashboard and networktables. SmartDashboard.putData(m_bangBangControler); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/Robot.java index a8d2d9888a4..bb8cdc7003c 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java index e9a1ae21209..208a9d4ea91 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java index 563235c2e1d..5e09be27cc9 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java @@ -25,17 +25,11 @@ public class Robot extends TimedRobot { private final XboxController m_controller = new XboxController(0); private final Timer m_timer = new Timer(); + /** Called once at the beginning of the robot program. */ public Robot() { SendableRegistry.addChild(m_robotDrive, m_leftDrive); SendableRegistry.addChild(m_robotDrive, m_rightDrive); - } - /** - * This function is run when the robot is first started up and should be used for any - * initialization code. - */ - @Override - public void robotInit() { // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java index 7d00c274e57..66a0e6c487c 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java @@ -36,13 +36,11 @@ public class Robot extends TimedRobot { private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort); private final Joystick m_joystick = new Joystick(kJoystickPort); + /** Called once at the beginning of the robot program. */ public Robot() { SendableRegistry.addChild(m_robotDrive, m_leftDrive); SendableRegistry.addChild(m_robotDrive, m_rightDrive); - } - @Override - public void robotInit() { m_gyro.setSensitivity(kVoltsPerDegreePerSecond); // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/Robot.java index bc6ede1b53b..dce5a58ab58 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java index a43523252c4..ff7a2553644 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java @@ -27,22 +27,17 @@ public class Robot extends TimedRobot { private static final int kGyroPort = 0; private static final int kJoystickPort = 0; - private MecanumDrive m_robotDrive; + private final MecanumDrive m_robotDrive; private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort); private final Joystick m_joystick = new Joystick(kJoystickPort); - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { PWMSparkMax frontLeft = new PWMSparkMax(kFrontLeftChannel); PWMSparkMax rearLeft = new PWMSparkMax(kRearLeftChannel); PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel); PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel); - SendableRegistry.addChild(m_robotDrive, frontLeft); - SendableRegistry.addChild(m_robotDrive, rearLeft); - SendableRegistry.addChild(m_robotDrive, frontRight); - SendableRegistry.addChild(m_robotDrive, rearRight); - // Invert the right side motors. // You may need to change or remove this to match your robot. frontRight.setInverted(true); @@ -51,6 +46,11 @@ public void robotInit() { m_robotDrive = new MecanumDrive(frontLeft::set, rearLeft::set, frontRight::set, rearRight::set); m_gyro.setSensitivity(kVoltsPerDegreePerSecond); + + SendableRegistry.addChild(m_robotDrive, frontLeft); + SendableRegistry.addChild(m_robotDrive, rearLeft); + SendableRegistry.addChild(m_robotDrive, frontRight); + SendableRegistry.addChild(m_robotDrive, rearRight); } /** Mecanum drive is used with the gyro angle as an input. */ diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/Robot.java index 4fb6d1b9228..e93c66c119b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/Robot.java @@ -19,14 +19,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/Robot.java index 09617df5a5c..f16db21359d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/Robot.java @@ -19,14 +19,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/httpcamera/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/httpcamera/Robot.java index dd4bcda3268..0657499dd4f 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/httpcamera/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/httpcamera/Robot.java @@ -22,8 +22,8 @@ public class Robot extends TimedRobot { Thread m_visionThread; - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { m_visionThread = new Thread( () -> { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Robot.java index e6e8b65ccdd..f50c8a33e45 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Robot.java @@ -22,8 +22,8 @@ public class Robot extends TimedRobot { Thread m_visionThread; - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { m_visionThread = new Thread( () -> { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Robot.java index 527fe3125c5..abc8e1f03d0 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java index 77aa0cedb71..871ce1e2bc8 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java @@ -19,21 +19,16 @@ public class Robot extends TimedRobot { private static final int kJoystickChannel = 0; - private MecanumDrive m_robotDrive; - private Joystick m_stick; + private final MecanumDrive m_robotDrive; + private final Joystick m_stick; - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { PWMSparkMax frontLeft = new PWMSparkMax(kFrontLeftChannel); PWMSparkMax rearLeft = new PWMSparkMax(kRearLeftChannel); PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel); PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel); - SendableRegistry.addChild(m_robotDrive, frontLeft); - SendableRegistry.addChild(m_robotDrive, rearLeft); - SendableRegistry.addChild(m_robotDrive, frontRight); - SendableRegistry.addChild(m_robotDrive, rearRight); - // Invert the right side motors. // You may need to change or remove this to match your robot. frontRight.setInverted(true); @@ -42,6 +37,11 @@ public void robotInit() { m_robotDrive = new MecanumDrive(frontLeft::set, rearLeft::set, frontRight::set, rearRight::set); m_stick = new Joystick(kJoystickChannel); + + SendableRegistry.addChild(m_robotDrive, frontLeft); + SendableRegistry.addChild(m_robotDrive, rearLeft); + SendableRegistry.addChild(m_robotDrive, frontRight); + SendableRegistry.addChild(m_robotDrive, rearRight); } @Override diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java index 264b8ad9fec..034db298c69 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java @@ -33,11 +33,11 @@ public class Robot extends TimedRobot { private final Encoder m_elevatorEncoder = new Encoder(0, 1); private final Joystick m_joystick = new Joystick(0); - private MechanismLigament2d m_elevator; - private MechanismLigament2d m_wrist; + private final MechanismLigament2d m_elevator; + private final MechanismLigament2d m_wrist; - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { m_elevatorEncoder.setDistancePerPulse(kMetersPerPulse); // the main mechanism object diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java index cbb4babbdf0..db79f6d5c7d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java @@ -26,12 +26,12 @@ public class Robot extends TimedRobot { private static final int kEncoderPortA = 0; private static final int kEncoderPortB = 1; - private PWMSparkMax m_motor; - private Joystick m_joystick; - private Encoder m_encoder; + private final PWMSparkMax m_motor; + private final Joystick m_joystick; + private final Encoder m_encoder; - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { m_motor = new PWMSparkMax(kMotorPort); m_joystick = new Joystick(kJoystickPort); m_encoder = new Encoder(kEncoderPortA, kEncoderPortB); @@ -49,6 +49,7 @@ public void robotPeriodic() { SmartDashboard.putNumber("Encoder", m_encoder.getDistance()); } + /** The teleop periodic function is called every control packet in teleop. */ @Override public void teleopPeriodic() { m_motor.set(m_joystick.getY()); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Robot.java index a025c5616e7..982e88bc5f7 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Robot.java @@ -10,11 +10,10 @@ /** * Uses the CameraServer class to automatically capture video from a USB webcam and send it to the * FRC dashboard without doing any vision processing. This is the easiest way to get camera images - * to the dashboard. Just add this to the robotInit() method in your program. + * to the dashboard. Just add this to the robot class constructor. */ public class Robot extends TimedRobot { - @Override - public void robotInit() { + public Robot() { CameraServer.startAutomaticCapture(); } } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java index 4c8ffbcd563..a4273a481ae 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java @@ -42,7 +42,7 @@ public class RapidReactCommandBot { * Use this method to define bindings between conditions and commands. These are useful for * automating robot behaviors based on button and sensor input. * - *

Should be called during {@link Robot#robotInit()}. + *

Should be called in the robot class constructor. * *

Event binding methods are available on the {@link Trigger} class. */ diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java index 049798cad6d..bb0e24e5010 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java @@ -27,8 +27,7 @@ public class Robot extends TimedRobot { * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Configure default commands and condition bindings on robot startup m_robot.configureBindings(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java index 33e12b2bfae..c00593308b9 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java @@ -16,14 +16,13 @@ */ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/selectcommand/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/selectcommand/Robot.java index 1a89f2cbb66..7bf5f4ce653 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/selectcommand/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/selectcommand/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java index 436d72685d4..8825b687444 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java @@ -26,10 +26,10 @@ public class Robot extends TimedRobot { private final PWMSparkMax m_elevatorMotor = new PWMSparkMax(2); private final AnalogPotentiometer m_elevatorPot = new AnalogPotentiometer(0); - private GenericEntry m_maxSpeed; + private final GenericEntry m_maxSpeed; - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { SendableRegistry.addChild(m_tankDrive, m_leftDriveMotor); SendableRegistry.addChild(m_tankDrive, m_rightDriveMotor); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java index 0227c3bfc4a..85953c63579 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java @@ -28,10 +28,10 @@ public class Robot extends TimedRobot { private final Drivetrain m_drive = new Drivetrain(); private final LTVUnicycleController m_feedback = new LTVUnicycleController(0.020); private final Timer m_timer = new Timer(); - private Trajectory m_trajectory; + private final Trajectory m_trajectory; - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { m_trajectory = TrajectoryGenerator.generateTrajectory( new Pose2d(2, 2, Rotation2d.kZero), diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/solenoid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/solenoid/Robot.java index 0b791c5120b..d4346f02bc7 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/solenoid/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/solenoid/Robot.java @@ -44,8 +44,8 @@ public class Robot extends TimedRobot { static final int kDoubleSolenoidReverseButton = 3; static final int kCompressorButton = 4; - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { // Publish elements to shuffleboard. ShuffleboardTab tab = Shuffleboard.getTab("Pneumatics"); tab.add("Single Solenoid", m_solenoid); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacearm/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacearm/Robot.java index b0314305170..77251079354 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacearm/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacearm/Robot.java @@ -101,8 +101,7 @@ public class Robot extends TimedRobot { // A joystick to read the trigger from. private final Joystick m_joystick = new Joystick(kJoystickPort); - @Override - public void robotInit() { + public Robot() { // We go 2 pi radians in 1 rotation, or 4096 counts. m_encoder.setDistancePerPulse(Math.PI * 2 / 4096.0); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceelevator/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceelevator/Robot.java index 0e9c045c9ca..f9bd7bf3603 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceelevator/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceelevator/Robot.java @@ -109,8 +109,7 @@ public class Robot extends TimedRobot { // A joystick to read the trigger from. private final Joystick m_joystick = new Joystick(kJoystickPort); - @Override - public void robotInit() { + public Robot() { // Circumference = pi * d, so distance per click = pi * d / counts m_encoder.setDistancePerPulse(Math.PI * 2 * kDrumRadius / 4096.0); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java index 94566eac348..73226a6af01 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java @@ -81,8 +81,7 @@ public class Robot extends TimedRobot { // A joystick to read the trigger from. private final Joystick m_joystick = new Joystick(kJoystickPort); - @Override - public void robotInit() { + public Robot() { // We go 2 pi radians per 4096 clicks. m_encoder.setDistancePerPulse(2.0 * Math.PI / 4096.0); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java index 3a073fe9d5e..2a9d8f2afa4 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java @@ -76,8 +76,7 @@ public class Robot extends TimedRobot { // A joystick to read the trigger from. private final Joystick m_joystick = new Joystick(kJoystickPort); - @Override - public void robotInit() { + public Robot() { // We go 2 pi radians per 4096 clicks. m_encoder.setDistancePerPulse(2.0 * Math.PI / 4096.0); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Robot.java index ab57b74d995..5dba8272e3d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/Robot.java index 0b0f1428913..90e18354ed3 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/Robot.java @@ -23,8 +23,7 @@ public class Robot extends TimedRobot { * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Configure default commands and condition bindings on robot startup m_robot.configureBindings(); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/SysIdRoutineBot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/SysIdRoutineBot.java index 93496fdcc37..7537c0bf937 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/SysIdRoutineBot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysid/SysIdRoutineBot.java @@ -31,7 +31,7 @@ public class SysIdRoutineBot { * Use this method to define bindings between conditions and commands. These are useful for * automating robot behaviors based on button and sensor input. * - *

Should be called during {@link Robot#robotInit()}. + *

Should be called in the robot class constructor. * *

Event binding methods are available on the {@link Trigger} class. */ diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java index a217f51b559..0e9143df89a 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java @@ -15,18 +15,15 @@ * the code necessary to operate a robot with tank drive. */ public class Robot extends TimedRobot { - private DifferentialDrive m_robotDrive; - private Joystick m_leftStick; - private Joystick m_rightStick; + private final DifferentialDrive m_robotDrive; + private final Joystick m_leftStick; + private final Joystick m_rightStick; private final PWMSparkMax m_leftMotor = new PWMSparkMax(0); private final PWMSparkMax m_rightMotor = new PWMSparkMax(1); - @Override - public void robotInit() { - SendableRegistry.addChild(m_robotDrive, m_leftMotor); - SendableRegistry.addChild(m_robotDrive, m_rightMotor); - + /** Called once at the beginning of the robot program. */ + public Robot() { // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. @@ -35,6 +32,9 @@ public void robotInit() { m_robotDrive = new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); m_leftStick = new Joystick(0); m_rightStick = new Joystick(1); + + SendableRegistry.addChild(m_robotDrive, m_leftMotor); + SendableRegistry.addChild(m_robotDrive, m_rightMotor); } @Override diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java index c1a850c5f70..6ed1ae1dfce 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java @@ -21,8 +21,8 @@ public class Robot extends TimedRobot { new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final XboxController m_driverController = new XboxController(0); - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { SendableRegistry.addChild(m_robotDrive, m_leftMotor); SendableRegistry.addChild(m_robotDrive, m_rightMotor); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java index edc81ab7244..602e58abe5b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java @@ -17,8 +17,8 @@ public class Robot extends TimedRobot { // Creates a ping-response Ultrasonic object on DIO 1 and 2. Ultrasonic m_rangeFinder = new Ultrasonic(1, 2); - @Override - public void robotInit() { + /** Called once at the beginning of the robot program. */ + public Robot() { // Add the ultrasonic on the "Sensors" tab of the dashboard // Data will update automatically Shuffleboard.getTab("Sensors").add(m_rangeFinder); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/Robot.java index daf5d32d193..4b908acdd5f 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java index 8542096ba22..eb8a49f5194 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/Robot.java index f682ec87bd5..753f54f3623 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/Robot.java @@ -11,10 +11,9 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; - @Override - public void robotInit() { + public Robot() { m_robotContainer = new RobotContainer(); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/EducationalRobot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/EducationalRobot.java index bb40caae8d2..29c4022dec9 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/EducationalRobot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/EducationalRobot.java @@ -12,7 +12,7 @@ /** Educational robot base class. */ public class EducationalRobot extends RobotBase { - public void robotInit() {} + public EducationalRobot() {} public void disabled() {} @@ -34,8 +34,6 @@ public void test() { @Override public void startCompetition() { - robotInit(); - DriverStationModeThread modeThread = new DriverStationModeThread(); int event = WPIUtilJNI.createEvent(false, false); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/Robot.java index 0643977fedf..c210de06f38 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/Robot.java @@ -14,8 +14,7 @@ public class Robot extends EducationalRobot { * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() {} + public Robot() {} /** This function is run when the robot is enabled. */ @Override diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/robotbaseskeleton/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/robotbaseskeleton/Robot.java index f08986476ac..bc0d9fea031 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/robotbaseskeleton/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/robotbaseskeleton/Robot.java @@ -15,7 +15,7 @@ * package after creating this project, you must also update the build.gradle file in the project. */ public class Robot extends RobotBase { - public void robotInit() {} + public Robot() {} public void disabled() {} @@ -29,8 +29,6 @@ public void test() {} @Override public void startCompetition() { - robotInit(); - DriverStationModeThread modeThread = new DriverStationModeThread(); int event = WPIUtilJNI.createEvent(false, false); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/Robot.java index fd393540d79..f6739e96158 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java index 5a84915d300..a9a777e42a4 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java @@ -12,7 +12,7 @@ /** Educational robot base class. */ public class EducationalRobot extends RobotBase { - public void robotInit() {} + public EducationalRobot() {} public void disabled() {} @@ -34,8 +34,6 @@ public void test() { @Override public void startCompetition() { - robotInit(); - DriverStationModeThread modeThread = new DriverStationModeThread(); int event = WPIUtilJNI.createEvent(false, false); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/Robot.java index be58b7270b5..cbec18dd875 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/Robot.java @@ -14,8 +14,7 @@ public class Robot extends EducationalRobot { * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() {} + public Robot() {} /** This function is run when the robot is enabled. */ @Override diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/Robot.java index 571bbc3ff52..0328c06d3bb 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/Robot.java @@ -26,8 +26,7 @@ public class Robot extends TimedRobot { * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { m_chooser.setDefaultOption("Default Auto", kDefaultAuto); m_chooser.addOption("My Auto", kCustomAuto); SmartDashboard.putData("Auto choices", m_chooser); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java index 92b3075ba6b..d8ddbaed236 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java @@ -24,8 +24,7 @@ public class Robot extends TimedRobot { * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { m_chooser.setDefaultOption("Default Auto", kDefaultAuto); m_chooser.addOption("My Auto", kCustomAuto); SmartDashboard.putData("Auto choices", m_chooser); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java index 4e0a8fea729..4f1c23b10c5 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java @@ -17,8 +17,7 @@ public class Robot extends TimedRobot { * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() {} + public Robot() {} @Override public void robotPeriodic() {} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timeslice/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timeslice/Robot.java index 661a06b75fb..9646e6aac13 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timeslice/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timeslice/Robot.java @@ -38,14 +38,7 @@ public Robot() { // Total usage: 5 ms (robot) + 2 ms (controller 1) + 2 ms (controller 2) // = 9 ms -> 90% allocated - } - /** - * This function is run when the robot is first started up and should be used for any - * initialization code. - */ - @Override - public void robotInit() { m_chooser.setDefaultOption("Default Auto", kDefaultAuto); m_chooser.addOption("My Auto", kCustomAuto); SmartDashboard.putData("Auto choices", m_chooser); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timesliceskeleton/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timesliceskeleton/Robot.java index 37ea2b5c34b..a35eab6102d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timesliceskeleton/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timesliceskeleton/Robot.java @@ -34,13 +34,6 @@ public Robot() { // 9 ms / 10 ms -> 90% allocated } - /** - * This function is run when the robot is first started up and should be used for any - * initialization code. - */ - @Override - public void robotInit() {} - @Override public void robotPeriodic() {} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpcommandbased/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpcommandbased/Robot.java index f7950f559e7..2f8147b7439 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpcommandbased/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpcommandbased/Robot.java @@ -17,14 +17,13 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; - private RobotContainer m_robotContainer; + private final RobotContainer m_robotContainer; /** * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/EducationalRobot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/EducationalRobot.java index 4b44707d7d3..0a6245c0894 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/EducationalRobot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/EducationalRobot.java @@ -12,7 +12,7 @@ /** Educational robot base class. */ public class EducationalRobot extends RobotBase { - public void robotInit() {} + public EducationalRobot() {} public void disabled() {} @@ -34,8 +34,6 @@ public void test() { @Override public void startCompetition() { - robotInit(); - DriverStationModeThread modeThread = new DriverStationModeThread(); int event = WPIUtilJNI.createEvent(false, false); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/Robot.java index 66c28069523..977756d37c3 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/Robot.java @@ -14,8 +14,7 @@ public class Robot extends EducationalRobot { * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() {} + public Robot() {} /** This function is run when the robot is enabled. */ @Override diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrptimed/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrptimed/Robot.java index f3b6d57d436..9559f54806d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrptimed/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrptimed/Robot.java @@ -26,8 +26,7 @@ public class Robot extends TimedRobot { * This function is run when the robot is first started up and should be used for any * initialization code. */ - @Override - public void robotInit() { + public Robot() { m_chooser.setDefaultOption("Default Auto", kDefaultAuto); m_chooser.addOption("My Auto", kCustomAuto); SmartDashboard.putData("Auto choices", m_chooser); From 15001afb312e13266749f2ded35944e475804b02 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 16 Jul 2024 22:56:36 -0700 Subject: [PATCH 10/10] [wpilib] Fix repeat TimedRobot callbacks on loop overrun (#4101) If one of the *Init() functions takes several multiples of the nominal loop time, the callbacks after that will run, then increment their expiration time by the nominal loop time. Since the new expiration time is still in the past, this will cause the callback to get repeatedly run in quick succession until its expiration time catches up with the current time. This change keeps incrementing the expiration time until it's in the future, which will avoid repeated runs. This doesn't delay other callbacks, so they'll get a chance to run once before their expiration times are corrected. The other option is correcting all the expiration times at once, which would starve the other callbacks even longer so that the callback scheduling returns to a regular cadence sooner. The problem with this approach is if a previous callback overruns the start of the next callback, the next callback could potentially never get a chance to run. --- wpilibc/src/main/native/cpp/TimedRobot.cpp | 33 +++++++---- .../src/main/native/include/frc/TimedRobot.h | 23 ++++---- .../edu/wpi/first/wpilibj/TimedRobot.java | 56 +++++++++++-------- 3 files changed, 66 insertions(+), 46 deletions(-) diff --git a/wpilibc/src/main/native/cpp/TimedRobot.cpp b/wpilibc/src/main/native/cpp/TimedRobot.cpp index 0b7b9cb3a2b..538d1b2cf47 100644 --- a/wpilibc/src/main/native/cpp/TimedRobot.cpp +++ b/wpilibc/src/main/native/cpp/TimedRobot.cpp @@ -14,7 +14,6 @@ #include #include "frc/Errors.h" -#include "frc/Timer.h" using namespace frc; @@ -37,29 +36,36 @@ void TimedRobot::StartCompetition() { auto callback = m_callbacks.pop(); int32_t status = 0; - HAL_UpdateNotifierAlarm( - m_notifier, static_cast(callback.expirationTime * 1e6), - &status); + HAL_UpdateNotifierAlarm(m_notifier, callback.expirationTime.count(), + &status); FRC_CheckErrorStatus(status, "UpdateNotifierAlarm"); - uint64_t curTime = HAL_WaitForNotifierAlarm(m_notifier, &status); - if (curTime == 0 || status != 0) { + std::chrono::microseconds currentTime{ + HAL_WaitForNotifierAlarm(m_notifier, &status)}; + if (currentTime.count() == 0 || status != 0) { break; } callback.func(); - callback.expirationTime += callback.period; + // Increment the expiration time by the number of full periods it's behind + // plus one to avoid rapid repeat fires from a large loop overrun. We assume + // currentTime ≥ expirationTime rather than checking for it since the + // callback wouldn't be running otherwise. + callback.expirationTime += + callback.period + (currentTime - callback.expirationTime) / + callback.period * callback.period; m_callbacks.push(std::move(callback)); // Process all other callbacks that are ready to run - while (static_cast(m_callbacks.top().expirationTime * 1e6) <= - curTime) { + while (m_callbacks.top().expirationTime <= currentTime) { callback = m_callbacks.pop(); callback.func(); - callback.expirationTime += callback.period; + callback.expirationTime += + callback.period + (currentTime - callback.expirationTime) / + callback.period * callback.period; m_callbacks.push(std::move(callback)); } } @@ -71,7 +77,7 @@ void TimedRobot::EndCompetition() { } TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) { - m_startTime = Timer::GetFPGATimestamp(); + m_startTime = std::chrono::microseconds{RobotController::GetFPGATime()}; AddPeriodic([=, this] { LoopFunc(); }, period); int32_t status = 0; @@ -94,5 +100,8 @@ TimedRobot::~TimedRobot() { void TimedRobot::AddPeriodic(std::function callback, units::second_t period, units::second_t offset) { - m_callbacks.emplace(callback, m_startTime, period, offset); + m_callbacks.emplace( + callback, m_startTime, + std::chrono::microseconds{static_cast(period.value() * 1e6)}, + std::chrono::microseconds{static_cast(offset.value() * 1e6)}); } diff --git a/wpilibc/src/main/native/include/frc/TimedRobot.h b/wpilibc/src/main/native/include/frc/TimedRobot.h index dcc510af2b8..647285474ad 100644 --- a/wpilibc/src/main/native/include/frc/TimedRobot.h +++ b/wpilibc/src/main/native/include/frc/TimedRobot.h @@ -4,6 +4,7 @@ #pragma once +#include #include #include #include @@ -14,7 +15,7 @@ #include #include "frc/IterativeRobotBase.h" -#include "frc/Timer.h" +#include "frc/RobotController.h" namespace frc { @@ -73,8 +74,8 @@ class TimedRobot : public IterativeRobotBase { class Callback { public: std::function func; - units::second_t period; - units::second_t expirationTime; + std::chrono::microseconds period; + std::chrono::microseconds expirationTime; /** * Construct a callback container. @@ -84,15 +85,15 @@ class TimedRobot : public IterativeRobotBase { * @param period The period at which to run the callback. * @param offset The offset from the common starting time. */ - Callback(std::function func, units::second_t startTime, - units::second_t period, units::second_t offset) + Callback(std::function func, std::chrono::microseconds startTime, + std::chrono::microseconds period, std::chrono::microseconds offset) : func{std::move(func)}, period{period}, - expirationTime{startTime + offset + - units::math::floor( - (Timer::GetFPGATimestamp() - startTime) / period) * - period + - period} {} + expirationTime( + startTime + offset + period + + (std::chrono::microseconds{frc::RobotController::GetFPGATime()} - + startTime) / + period * period) {} bool operator>(const Callback& rhs) const { return expirationTime > rhs.expirationTime; @@ -100,7 +101,7 @@ class TimedRobot : public IterativeRobotBase { }; hal::Handle m_notifier; - units::second_t m_startTime; + std::chrono::microseconds m_startTime; wpi::priority_queue, std::greater> m_callbacks; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java index 180a17b457d..2251d712d9f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java @@ -26,26 +26,26 @@ public class TimedRobot extends IterativeRobotBase { @SuppressWarnings("MemberName") static class Callback implements Comparable { public Runnable func; - public double period; - public double expirationTime; + public long period; + public long expirationTime; /** * Construct a callback container. * * @param func The callback to run. - * @param startTimeSeconds The common starting point for all callback scheduling in seconds. - * @param periodSeconds The period at which to run the callback in seconds. - * @param offsetSeconds The offset from the common starting time in seconds. + * @param startTimeSeconds The common starting point for all callback scheduling in + * microseconds. + * @param periodSeconds The period at which to run the callback in microseconds. + * @param offsetSeconds The offset from the common starting time in microseconds. */ - Callback(Runnable func, double startTimeSeconds, double periodSeconds, double offsetSeconds) { + Callback(Runnable func, long startTimeUs, long periodUs, long offsetUs) { this.func = func; - this.period = periodSeconds; + this.period = periodUs; this.expirationTime = - startTimeSeconds - + offsetSeconds - + Math.floor((Timer.getFPGATimestamp() - startTimeSeconds) / this.period) - * this.period - + this.period; + startTimeUs + + offsetUs + + this.period + + (RobotController.getFPGATime() - startTimeUs) / this.period * this.period; } @Override @@ -62,7 +62,7 @@ public int hashCode() { public int compareTo(Callback rhs) { // Elements with sooner expiration times are sorted as lesser. The head of // Java's PriorityQueue is the least element. - return Double.compare(expirationTime, rhs.expirationTime); + return Long.compare(expirationTime, rhs.expirationTime); } } @@ -73,7 +73,7 @@ public int compareTo(Callback rhs) { // just passed to the JNI bindings. private final int m_notifier = NotifierJNI.initializeNotifier(); - private double m_startTime; + private long m_startTimeUs; private final PriorityQueue m_callbacks = new PriorityQueue<>(); @@ -89,7 +89,7 @@ protected TimedRobot() { */ protected TimedRobot(double period) { super(period); - m_startTime = Timer.getFPGATimestamp(); + m_startTimeUs = RobotController.getFPGATime(); addPeriodic(this::loopFunc, period); NotifierJNI.setNotifierName(m_notifier, "TimedRobot"); @@ -122,25 +122,33 @@ public void startCompetition() { // at the end of the loop. var callback = m_callbacks.poll(); - NotifierJNI.updateNotifierAlarm(m_notifier, (long) (callback.expirationTime * 1e6)); + NotifierJNI.updateNotifierAlarm(m_notifier, callback.expirationTime); - long curTime = NotifierJNI.waitForNotifierAlarm(m_notifier); - if (curTime == 0) { + long currentTime = NotifierJNI.waitForNotifierAlarm(m_notifier); + if (currentTime == 0) { break; } callback.func.run(); - callback.expirationTime += callback.period; + // Increment the expiration time by the number of full periods it's behind + // plus one to avoid rapid repeat fires from a large loop overrun. We + // assume currentTime ≥ expirationTime rather than checking for it since + // the callback wouldn't be running otherwise. + callback.expirationTime += + callback.period + + (currentTime - callback.expirationTime) / callback.period * callback.period; m_callbacks.add(callback); // Process all other callbacks that are ready to run - while ((long) (m_callbacks.peek().expirationTime * 1e6) <= curTime) { + while (m_callbacks.peek().expirationTime <= currentTime) { callback = m_callbacks.poll(); callback.func.run(); - callback.expirationTime += callback.period; + callback.expirationTime += + callback.period + + (currentTime - callback.expirationTime) / callback.period * callback.period; m_callbacks.add(callback); } } @@ -162,7 +170,7 @@ public void endCompetition() { * @param periodSeconds The period at which to run the callback in seconds. */ public final void addPeriodic(Runnable callback, double periodSeconds) { - m_callbacks.add(new Callback(callback, m_startTime, periodSeconds, 0.0)); + m_callbacks.add(new Callback(callback, m_startTimeUs, (long) (periodSeconds * 1e6), 0)); } /** @@ -177,7 +185,9 @@ public final void addPeriodic(Runnable callback, double periodSeconds) { * scheduling a callback in a different timeslot relative to TimedRobot. */ public final void addPeriodic(Runnable callback, double periodSeconds, double offsetSeconds) { - m_callbacks.add(new Callback(callback, m_startTime, periodSeconds, offsetSeconds)); + m_callbacks.add( + new Callback( + callback, m_startTimeUs, (long) (periodSeconds * 1e6), (long) (offsetSeconds * 1e6))); } /**