diff --git a/.github/labeler.yml b/.github/labeler.yml index 642615aa62..9a1881e4d3 100644 --- a/.github/labeler.yml +++ b/.github/labeler.yml @@ -51,3 +51,12 @@ 'component: wpiutil': - changed-files: - any-glob-to-any-file: wpiutil/** +'component: wpical': +- changed-files: + - any-glob-to-any-file: wpical/** +'component: usage reporting': +- changed-files: + - any-glob-to-any-file: hal/src/generate/** +'attn: NI': +- changed-files: + - any-glob-to-any-file: hal/src/generate/** diff --git a/.github/workflows/aql/wpilib-mvn-development_unused.aql b/.github/workflows/aql/wpilib-mvn-development_unused.aql index 4fc627fbd3..365094310c 100644 --- a/.github/workflows/aql/wpilib-mvn-development_unused.aql +++ b/.github/workflows/aql/wpilib-mvn-development_unused.aql @@ -3,7 +3,7 @@ { "aql": { "items.find": { - "repo": "wpilib-mvn-development", + "repo": "wpilib-mvn-development-local", "path": { "$nmatch":"*edu/wpi/first/thirdparty*" }, "$or":[ { diff --git a/.github/workflows/artifactory-nightly-cleanup.yml b/.github/workflows/artifactory-nightly-cleanup.yml index f76ec77db7..7f694b6d75 100644 --- a/.github/workflows/artifactory-nightly-cleanup.yml +++ b/.github/workflows/artifactory-nightly-cleanup.yml @@ -2,6 +2,8 @@ name: Artifactory Nightly Cleanup on: workflow_dispatch: + schedule: + - cron: '15 2 * * *' jobs: wpilib-mvn-development_unused_cleanup: diff --git a/.github/workflows/labeler.yml b/.github/workflows/labeler.yml index e57cd86e2b..526323cea6 100644 --- a/.github/workflows/labeler.yml +++ b/.github/workflows/labeler.yml @@ -1,6 +1,6 @@ name: "Pull Request Labeler" on: -- pull_request_target + - pull_request_target jobs: labeler: @@ -9,4 +9,6 @@ jobs: pull-requests: write runs-on: ubuntu-latest steps: - - uses: actions/labeler@v5 + - uses: actions/labeler@v5 + with: + sync-labels: true diff --git a/.github/workflows/upstream-utils.yml b/.github/workflows/upstream-utils.yml index fc8108e013..6409faba78 100644 --- a/.github/workflows/upstream-utils.yml +++ b/.github/workflows/upstream-utils.yml @@ -120,12 +120,6 @@ jobs: ./mpack.py clone ./mpack.py copy-src ./mpack.py format-patch - - name: Run stack_walker.py - run: | - cd upstream_utils - ./stack_walker.py clone - ./stack_walker.py copy-src - ./stack_walker.py format-patch - name: Run memory.py run: | cd upstream_utils diff --git a/.gitignore b/.gitignore index 3cf9f62103..0d50414a43 100644 --- a/.gitignore +++ b/.gitignore @@ -255,3 +255,6 @@ bazel_auth.rc # ctest /Testing/ + +# Meson +.meson-subproject* diff --git a/ThirdPartyNotices.txt b/ThirdPartyNotices.txt index 01e52c7fd3..91bd7a2fb1 100644 --- a/ThirdPartyNotices.txt +++ b/ThirdPartyNotices.txt @@ -33,7 +33,6 @@ jQuery wpinet/src/main/native/resources/jquery-* popper.js wpinet/src/main/native/resources/popper-* units wpimath/src/main/native/include/units/ Eigen wpimath/src/main/native/thirdparty/eigen/include/ -StackWalker wpiutil/src/main/native/windows/StackWalker.* Team 254 Library wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryParameterizer.java wpimath/src/main/native/include/frc/spline/SplineParameterizer.h @@ -54,6 +53,7 @@ nanopb wpiutil/src/main/native/thirdparty/nanopb protobuf wpiutil/src/main/native/thirdparty/protobuf mrcal wpical/src/main/native/thirdparty/mrcal libdogleg wpical/src/main/native/thirdparty/libdogleg +Simd hal/src/main/native/athena/simd Additionally, glfw, memory, and nanopb were all modified for use in WPILib. @@ -1025,35 +1025,6 @@ Exhibit B - "Incompatible With Secondary Licenses" Notice defined by the Mozilla Public License, v. 2.0. -=================== -StackWalker License -=================== -Copyright (c) 2005-2013, Jochen Kalmbach -All rights reserved. - -Redistribution and use in source and binary forms, with or without modification, -are permitted provided that the following conditions are met: - -Redistributions of source code must retain the above copyright notice, -this list of conditions and the following disclaimer. -Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the following disclaimer in the documentation -and/or other materials provided with the distribution. -Neither the name of Jochen Kalmbach nor the names of its contributors may be -used to endorse or promote products derived from this software without -specific prior written permission. -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, -THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE -FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - ================ Team 254 Library ================ @@ -1702,3 +1673,29 @@ This program is free software: you can redistribute it and/or modify it under th This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details. The full text of the license is available at http://www.gnu.org/licenses + +============ +Simd License +============ + +MIT License + +Copyright (c) 2011-2017 Ihar Yermalayeu + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java b/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java index 63a516aa38..2050ed3e08 100644 --- a/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java +++ b/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java @@ -14,14 +14,16 @@ public enum AprilTagFields { k2023ChargedUp("2023-chargedup.json"), /** 2024 Crescendo. */ k2024Crescendo("2024-crescendo.json"), - /** 2025 Reefscape. */ - k2025Reefscape("2025-reefscape.json"); + /** 2025 Reefscape Welded (see TU 12). */ + k2025ReefscapeWelded("2025-reefscape-welded.json"), + /** 2025 Reefscape AndyMark (see TU 12). */ + k2025ReefscapeAndyMark("2025-reefscape-andymark.json"); /** Base resource directory. */ public static final String kBaseResourceDir = "/edu/wpi/first/apriltag/"; /** Alias to the current game. */ - public static final AprilTagFields kDefaultField = k2025Reefscape; + public static final AprilTagFields kDefaultField = k2025ReefscapeWelded; /** Resource filename. */ public final String m_resourceFile; diff --git a/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp b/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp index 04d7a78c60..8388210b25 100644 --- a/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp +++ b/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp @@ -133,7 +133,8 @@ namespace frc { std::string_view GetResource_2022_rapidreact_json(); std::string_view GetResource_2023_chargedup_json(); std::string_view GetResource_2024_crescendo_json(); -std::string_view GetResource_2025_reefscape_json(); +std::string_view GetResource_2025_reefscape_welded_json(); +std::string_view GetResource_2025_reefscape_andymark_json(); } // namespace frc @@ -149,8 +150,11 @@ AprilTagFieldLayout AprilTagFieldLayout::LoadField(AprilTagField field) { case AprilTagField::k2024Crescendo: fieldString = GetResource_2024_crescendo_json(); break; - case AprilTagField::k2025Reefscape: - fieldString = GetResource_2025_reefscape_json(); + case AprilTagField::k2025ReefscapeWelded: + fieldString = GetResource_2025_reefscape_welded_json(); + break; + case AprilTagField::k2025ReefscapeAndyMark: + fieldString = GetResource_2025_reefscape_andymark_json(); break; case AprilTagField::kNumFields: throw std::invalid_argument("Invalid Field"); diff --git a/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h b/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h index 94ac799c85..2e1f5cc795 100644 --- a/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h +++ b/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h @@ -20,10 +20,12 @@ enum class AprilTagField { k2023ChargedUp, /// 2024 Crescendo. k2024Crescendo, - /// 2025 Reefscape. - k2025Reefscape, + /// 2025 Reefscape AndyMark (see TU12). + k2025ReefscapeAndyMark, + /// 2025 Reefscape Welded (see TU12). + k2025ReefscapeWelded, /// Alias to the current game. - kDefaultField = k2025Reefscape, + kDefaultField = k2025ReefscapeWelded, // This is a placeholder for denoting the last supported field. This should // always be the last entry in the enum and should not be used by users diff --git a/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape-andymark.csv b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape-andymark.csv new file mode 100644 index 0000000000..76b77f4893 --- /dev/null +++ b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape-andymark.csv @@ -0,0 +1,23 @@ +ID,X,Y,Z,Z-Rotation,X-Rotation +1,656.98,24.73,58.5,126,0 +2,656.98,291.9,58.5,234,0 +3,452.4,316.21,51.25,270,0 +4,365.2,241.44,73.54,0,30 +5,365.2,75.19,73.54,0,30 +6,530.49,129.97,12.13,300,0 +7,546.87,158.3,12.13,0,0 +8,530.49,186.63,12.13,60,0 +9,497.77,186.63,12.13,120,0 +10,481.39,158.3,12.13,180,0 +11,497.77,129.97,12.13,240,0 +12,33.91,24.73,58.5,54,0 +13,33.91,291.9,58.5,306,0 +14,325.68,241.44,73.54,180,30 +15,325.68,75.19,73.54,180,30 +16,238.49,0.42,51.25,90,0 +17,160.39,129.97,12.13,240,0 +18,144,158.3,12.13,180,0 +19,160.39,186.63,12.13,120,0 +20,193.1,186.63,12.13,60,0 +21,209.49,158.3,12.13,0,0 +22,193.1,129.97,12.13,300,0 diff --git a/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape-andymark.json b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape-andymark.json new file mode 100644 index 0000000000..60b60e5e74 --- /dev/null +++ b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape-andymark.json @@ -0,0 +1,404 @@ +{ + "tags": [ + { + "ID": 1, + "pose": { + "translation": { + "x": 16.687292, + "y": 0.628142, + "z": 1.4859 + }, + "rotation": { + "quaternion": { + "W": 0.4539904997395468, + "X": 0.0, + "Y": 0.0, + "Z": 0.8910065241883678 + } + } + } + }, + { + "ID": 2, + "pose": { + "translation": { + "x": 16.687292, + "y": 7.414259999999999, + "z": 1.4859 + }, + "rotation": { + "quaternion": { + "W": -0.45399049973954675, + "X": -0.0, + "Y": 0.0, + "Z": 0.8910065241883679 + } + } + } + }, + { + "ID": 3, + "pose": { + "translation": { + "x": 11.49096, + "y": 8.031733999999998, + "z": 1.30175 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 4, + "pose": { + "translation": { + "x": 9.276079999999999, + "y": 6.132575999999999, + "z": 1.8679160000000001 + }, + "rotation": { + "quaternion": { + "W": 0.9659258262890683, + "X": 0.0, + "Y": 0.25881904510252074, + "Z": 0.0 + } + } + } + }, + { + "ID": 5, + "pose": { + "translation": { + "x": 9.276079999999999, + "y": 1.9098259999999998, + "z": 1.8679160000000001 + }, + "rotation": { + "quaternion": { + "W": 0.9659258262890683, + "X": 0.0, + "Y": 0.25881904510252074, + "Z": 0.0 + } + } + } + }, + { + "ID": 6, + "pose": { + "translation": { + "x": 13.474446, + "y": 3.3012379999999997, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": -0.8660254037844387, + "X": -0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + }, + { + "ID": 7, + "pose": { + "translation": { + "x": 13.890498, + "y": 4.0208200000000005, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 8, + "pose": { + "translation": { + "x": 13.474446, + "y": 4.740402, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 0.8660254037844387, + "X": 0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + }, + { + "ID": 9, + "pose": { + "translation": { + "x": 12.643358, + "y": 4.740402, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 0.5000000000000001, + "X": 0.0, + "Y": 0.0, + "Z": 0.8660254037844386 + } + } + } + }, + { + "ID": 10, + "pose": { + "translation": { + "x": 12.227305999999999, + "y": 4.0208200000000005, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 11, + "pose": { + "translation": { + "x": 12.643358, + "y": 3.3012379999999997, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": -0.4999999999999998, + "X": -0.0, + "Y": 0.0, + "Z": 0.8660254037844387 + } + } + } + }, + { + "ID": 12, + "pose": { + "translation": { + "x": 0.8613139999999999, + "y": 0.628142, + "z": 1.4859 + }, + "rotation": { + "quaternion": { + "W": 0.8910065241883679, + "X": 0.0, + "Y": 0.0, + "Z": 0.45399049973954675 + } + } + } + }, + { + "ID": 13, + "pose": { + "translation": { + "x": 0.8613139999999999, + "y": 7.414259999999999, + "z": 1.4859 + }, + "rotation": { + "quaternion": { + "W": -0.8910065241883678, + "X": -0.0, + "Y": 0.0, + "Z": 0.45399049973954686 + } + } + } + }, + { + "ID": 14, + "pose": { + "translation": { + "x": 8.272272, + "y": 6.132575999999999, + "z": 1.8679160000000001 + }, + "rotation": { + "quaternion": { + "W": 5.914589856893349e-17, + "X": -0.25881904510252074, + "Y": 1.5848095757158825e-17, + "Z": 0.9659258262890683 + } + } + } + }, + { + "ID": 15, + "pose": { + "translation": { + "x": 8.272272, + "y": 1.9098259999999998, + "z": 1.8679160000000001 + }, + "rotation": { + "quaternion": { + "W": 5.914589856893349e-17, + "X": -0.25881904510252074, + "Y": 1.5848095757158825e-17, + "Z": 0.9659258262890683 + } + } + } + }, + { + "ID": 16, + "pose": { + "translation": { + "x": 6.057646, + "y": 0.010667999999999999, + "z": 1.30175 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 17, + "pose": { + "translation": { + "x": 4.073905999999999, + "y": 3.3012379999999997, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": -0.4999999999999998, + "X": -0.0, + "Y": 0.0, + "Z": 0.8660254037844387 + } + } + } + }, + { + "ID": 18, + "pose": { + "translation": { + "x": 3.6576, + "y": 4.0208200000000005, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 19, + "pose": { + "translation": { + "x": 4.073905999999999, + "y": 4.740402, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 0.5000000000000001, + "X": 0.0, + "Y": 0.0, + "Z": 0.8660254037844386 + } + } + } + }, + { + "ID": 20, + "pose": { + "translation": { + "x": 4.904739999999999, + "y": 4.740402, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 0.8660254037844387, + "X": 0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + }, + { + "ID": 21, + "pose": { + "translation": { + "x": 5.321046, + "y": 4.0208200000000005, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 22, + "pose": { + "translation": { + "x": 4.904739999999999, + "y": 3.3012379999999997, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": -0.8660254037844387, + "X": -0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + } + ], + "field": { + "length": 17.548, + "width": 8.042 + } +} diff --git a/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape.csv b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape-welded.csv similarity index 100% rename from apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape.csv rename to apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape-welded.csv diff --git a/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape.json b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape-welded.json similarity index 100% rename from apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape.json rename to apriltag/src/main/native/resources/edu/wpi/first/apriltag/2025-reefscape-welded.json diff --git a/buildSrc/build.gradle b/buildSrc/build.gradle index 8a0ad0c1a9..36829299fb 100644 --- a/buildSrc/build.gradle +++ b/buildSrc/build.gradle @@ -9,5 +9,5 @@ repositories { } } dependencies { - implementation "edu.wpi.first:native-utils:2025.9.0" + implementation "edu.wpi.first:native-utils:2025.9.1" } diff --git a/buildSrc/src/main/groovy/WPIJREArtifact.groovy b/buildSrc/src/main/groovy/WPIJREArtifact.groovy index ad929daa64..c23248f035 100644 --- a/buildSrc/src/main/groovy/WPIJREArtifact.groovy +++ b/buildSrc/src/main/groovy/WPIJREArtifact.groovy @@ -28,7 +28,7 @@ public class WPIJREArtifact extends MavenArtifact { private boolean checkJreVersion = true; - private final String artifactLocation = "edu.wpi.first.jdk:roborio-2024:17.0.9u7-1" + private final String artifactLocation = "edu.wpi.first.jdk:roborio-2024:17.0.9u7-3" @Inject public WPIJREArtifact(String name, RemoteTarget target) { diff --git a/cmake/modules/CompileWarnings.cmake b/cmake/modules/CompileWarnings.cmake index fd4f9294ba..cadc9fe02e 100644 --- a/cmake/modules/CompileWarnings.cmake +++ b/cmake/modules/CompileWarnings.cmake @@ -46,7 +46,7 @@ macro(wpilib_target_warnings target) # Suppress warning "enumeration types with a fixed underlying type are a # Clang extension" - if(APPLE) + if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") target_compile_options(${target} PRIVATE $<$:-Wno-fixed-enum-extension>) endif() 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 index 2781c055c8..398569702e 100644 --- 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 @@ -68,7 +68,9 @@ public class AnnotationProcessor extends AbstractProcessor { customLoggers.putAll(processCustomLoggers(roundEnv, customLogger)); }); + // Get all root types (classes and interfaces), excluding packages and modules roundEnv.getRootElements().stream() + .filter(e -> e instanceof TypeElement) .filter( e -> processingEnv @@ -267,12 +269,18 @@ public class AnnotationProcessor extends AbstractProcessor { return false; } - processingEnv - .getMessager() - .printMessage( - Diagnostic.Kind.NOTE, - "[EPILOGUE] Excluded from logs because " + type + " is not a loggable data type", - element); + var classConfig = element.getEnclosingElement().getAnnotation(Logged.class); + + if (classConfig == null || classConfig.warnForNonLoggableTypes()) { + // Not loggable and not explicitly opted out of logging; print a warning message + processingEnv + .getMessager() + .printMessage( + Diagnostic.Kind.NOTE, + "[EPILOGUE] Excluded from logs because " + type + " is not a loggable data type", + element); + } + return true; } 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 index e7cb686f71..496a773095 100644 --- 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 @@ -71,6 +71,11 @@ public class LoggerGenerator { public Naming defaultNaming() { return Naming.USE_CODE_NAME; } + + @Override + public boolean warnForNonLoggableTypes() { + return false; + } }; public LoggerGenerator(ProcessingEnvironment processingEnv, List handlers) { 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 index ec4e52d5f4..8f1d9f2b19 100644 --- 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 @@ -1772,7 +1772,7 @@ class AnnotationProcessorTest { """ package edu.wpi.first.epilogue; - @Logged + @Logged(warnForNonLoggableTypes = true) class Example { Throwable t; } @@ -1974,6 +1974,37 @@ class AnnotationProcessorTest { assertLoggerGenerates(source, expectedRootLogger); } + @Test + void doesNotBreakWithPackageInfo() { + String source = + """ + package example; + + import edu.wpi.first.epilogue.*; + + @Logged + class Example {} + """; + + String packageInfo = """ + package example; + """; + + Compilation compilation = + javac() + .withOptions(kJavaVersionOptions) + .withProcessors(new AnnotationProcessor()) + .compile( + JavaFileObjects.forSourceString("example.Example", source), + JavaFileObjects.forSourceString("example.package-info", packageInfo)); + + assertThat(compilation).succeeded(); + compilation.generatedSourceFiles().stream() + .filter(jfo -> jfo.getName().contains("Example")) + .findFirst() + .orElseThrow(() -> new IllegalStateException("Logger file was not generated!")); + } + private void assertCompilationError( String message, long lineNumber, long col, Diagnostic diagnostic) { assertAll( 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 index 2d76c9bfbe..c939d019d3 100644 --- a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/Logged.java +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/Logged.java @@ -124,4 +124,12 @@ public @interface Logged { * for all logged fields and methods in an annotated class */ Naming defaultNaming() default Naming.USE_CODE_NAME; + + /** + * Class-level only: if {@link #strategy()} is {@link Strategy#OPT_OUT}, this can be used to quiet + * the warnings that are printed for non-loggable fields and methods detected within the class. + * + * @return true if warnings should be printed, or false if warnings should not be printed + */ + boolean warnForNonLoggableTypes() default false; } diff --git a/fieldImages/CMakeLists.txt b/fieldImages/CMakeLists.txt index 93f8e13695..f1d435c30e 100644 --- a/fieldImages/CMakeLists.txt +++ b/fieldImages/CMakeLists.txt @@ -36,13 +36,13 @@ endif() generate_resources( src/main/native/resources/edu/wpi/first/fields - generated/main/cpp + ${CMAKE_CURRENT_BINARY_DIR}/generated/main/cpp FIELDS fields field_images_resources_src ) -add_library(fieldImages src/main/native/cpp/fields.cpp ${field_images_resources_src}) +add_library(fieldImages ${field_images_resources_src} src/main/native/cpp/fields.cpp) set_target_properties(fieldImages PROPERTIES DEBUG_POSTFIX "d") set_property(TARGET fieldImages PROPERTY FOLDER "libraries") diff --git a/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java b/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java index 38f992a841..1294a7562a 100644 --- a/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java @@ -10,6 +10,13 @@ package edu.wpi.first.hal; * @see "hal/AddressableLED.h" */ public class AddressableLEDJNI extends JNIWrapper { + public static final int COLOR_ORDER_RGB = 0; + public static final int COLOR_ORDER_RBG = 1; + public static final int COLOR_ORDER_BGR = 2; + public static final int COLOR_ORDER_BRG = 3; + public static final int COLOR_ORDER_GBR = 4; + public static final int COLOR_ORDER_GRB = 5; + /** * Initialize Addressable LED using a PWM Digital handle. * @@ -27,6 +34,16 @@ public class AddressableLEDJNI extends JNIWrapper { */ public static native void free(int handle); + /** + * Sets the color order for the addressable LED output. The default order is GRB. + * + *

This will take effect on the next call to {@link #setData(int, byte[])}. + * + * @param handle the Addressable LED handle + * @param colorOrder the color order + */ + public static native void setColorOrder(int handle, int colorOrder); + /** * Sets the length of the LED strip. * diff --git a/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp b/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp index 1d9017da1c..e7459a2b86 100644 --- a/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp +++ b/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp @@ -15,6 +15,19 @@ using namespace wpi::java; static_assert(sizeof(jbyte) * 4 == sizeof(HAL_AddressableLEDData)); +static_assert(edu_wpi_first_hal_AddressableLEDJNI_COLOR_ORDER_RGB == + HAL_ALED_RGB); +static_assert(edu_wpi_first_hal_AddressableLEDJNI_COLOR_ORDER_RBG == + HAL_ALED_RBG); +static_assert(edu_wpi_first_hal_AddressableLEDJNI_COLOR_ORDER_BGR == + HAL_ALED_BGR); +static_assert(edu_wpi_first_hal_AddressableLEDJNI_COLOR_ORDER_BRG == + HAL_ALED_BRG); +static_assert(edu_wpi_first_hal_AddressableLEDJNI_COLOR_ORDER_GBR == + HAL_ALED_GBR); +static_assert(edu_wpi_first_hal_AddressableLEDJNI_COLOR_ORDER_GRB == + HAL_ALED_GRB); + extern "C" { /* * Class: edu_wpi_first_hal_AddressableLEDJNI @@ -46,6 +59,22 @@ Java_edu_wpi_first_hal_AddressableLEDJNI_free } } +/* + * Class: edu_wpi_first_hal_AddressableLEDJNI + * Method: setColorOrder + * Signature: (II)V + */ +JNIEXPORT void JNICALL +Java_edu_wpi_first_hal_AddressableLEDJNI_setColorOrder + (JNIEnv* env, jclass, jint handle, jint colorOrder) +{ + int32_t status = 0; + HAL_SetAddressableLEDColorOrder( + static_cast(handle), + static_cast(colorOrder), &status); + CheckStatus(env, status); +} + /* * Class: edu_wpi_first_hal_AddressableLEDJNI * Method: setLength diff --git a/hal/src/main/native/include/hal/AddressableLED.h b/hal/src/main/native/include/hal/AddressableLED.h index e1f6a5d465..c220795138 100644 --- a/hal/src/main/native/include/hal/AddressableLED.h +++ b/hal/src/main/native/include/hal/AddressableLED.h @@ -36,6 +36,17 @@ HAL_AddressableLEDHandle HAL_InitializeAddressableLED( */ void HAL_FreeAddressableLED(HAL_AddressableLEDHandle handle); +/** + * Sets the color order for the addressable LED output. The default order is + * GRB. This will take effect on the next call to HAL_WriteAddressableLEDData(). + * @param[in] handle the Addressable LED handle + * @param[in] colorOrder the color order + * @param[out] status the error code, or 0 for success + */ +void HAL_SetAddressableLEDColorOrder(HAL_AddressableLEDHandle handle, + HAL_AddressableLEDColorOrder colorOrder, + int32_t* status); + /** * Set the Addressable LED PWM Digital port. * diff --git a/hal/src/main/native/include/hal/AddressableLEDTypes.h b/hal/src/main/native/include/hal/AddressableLEDTypes.h index 48918f4b72..4dad3683c8 100644 --- a/hal/src/main/native/include/hal/AddressableLEDTypes.h +++ b/hal/src/main/native/include/hal/AddressableLEDTypes.h @@ -4,6 +4,7 @@ #pragma once +#include #include /** max length of LED strip supported by FPGA. */ @@ -16,3 +17,21 @@ struct HAL_AddressableLEDData { uint8_t r; ///< red value uint8_t padding; }; + +/** + * Order that color data is sent over the wire. + */ +HAL_ENUM(HAL_AddressableLEDColorOrder) { + HAL_ALED_RGB, + HAL_ALED_RBG, + HAL_ALED_BGR, + HAL_ALED_BRG, + HAL_ALED_GBR, + HAL_ALED_GRB +}; + +#ifdef __cplusplus +constexpr auto format_as(HAL_AddressableLEDColorOrder order) { + return static_cast(order); +} +#endif diff --git a/hal/src/main/native/sim/AddressableLED.cpp b/hal/src/main/native/sim/AddressableLED.cpp index bdc9a6924b..1682be48c4 100644 --- a/hal/src/main/native/sim/AddressableLED.cpp +++ b/hal/src/main/native/sim/AddressableLED.cpp @@ -91,6 +91,10 @@ void HAL_FreeAddressableLED(HAL_AddressableLEDHandle handle) { SimAddressableLEDData[led->index].initialized = false; } +void HAL_SetAddressableLEDColorOrder(HAL_AddressableLEDHandle handle, + HAL_AddressableLEDColorOrder colorOrder, + int32_t* status) {} + void HAL_SetAddressableLEDOutputPort(HAL_AddressableLEDHandle handle, HAL_DigitalHandle outputPort, int32_t* status) { diff --git a/hal/src/main/native/systemcore/AddressableLED.cpp b/hal/src/main/native/systemcore/AddressableLED.cpp index 31f11a0dec..cd31e46b52 100644 --- a/hal/src/main/native/systemcore/AddressableLED.cpp +++ b/hal/src/main/native/systemcore/AddressableLED.cpp @@ -30,6 +30,13 @@ HAL_AddressableLEDHandle HAL_InitializeAddressableLED( void HAL_FreeAddressableLED(HAL_AddressableLEDHandle handle) {} +void HAL_SetAddressableLEDColorOrder(HAL_AddressableLEDHandle handle, + HAL_AddressableLEDColorOrder colorOrder, + int32_t* status) { + *status = HAL_HANDLE_ERROR; + return; +} + void HAL_SetAddressableLEDOutputPort(HAL_AddressableLEDHandle handle, HAL_DigitalHandle outputPort, int32_t* status) { diff --git a/sysid/src/main/native/cpp/App.cpp b/sysid/src/main/native/cpp/App.cpp index 6d1b9285a3..178a0f726c 100644 --- a/sysid/src/main/native/cpp/App.cpp +++ b/sysid/src/main/native/cpp/App.cpp @@ -106,8 +106,10 @@ void Application(std::string_view saveDir) { auto analyzer = std::make_unique(storage, gLogger); logLoader->unload.connect([ds = dataSelector.get()] { ds->Reset(); }); - dataSelector->testdata = [_analyzer = analyzer.get()](auto data) { + dataSelector->testdata = [_analyzer = analyzer.get(), + ds = dataSelector.get()](auto data) { _analyzer->m_data = data; + _analyzer->SetMissingTests(ds->m_missingTests); _analyzer->AnalyzeData(); }; diff --git a/sysid/src/main/native/cpp/view/Analyzer.cpp b/sysid/src/main/native/cpp/view/Analyzer.cpp index 03b39171b2..726042586d 100644 --- a/sysid/src/main/native/cpp/view/Analyzer.cpp +++ b/sysid/src/main/native/cpp/view/Analyzer.cpp @@ -10,6 +10,7 @@ #include #include #include +#include #include #include @@ -251,6 +252,13 @@ void Analyzer::Display() { } break; } + case AnalyzerState::kMissingTestsError: { + CreateErrorPopup(m_errorPopup, m_exception); + if (!m_errorPopup) { + m_state = AnalyzerState::kWaitingForData; + } + break; + } case AnalyzerState::kGeneralDataError: case AnalyzerState::kTestDurationError: case AnalyzerState::kVelocityThresholdError: { @@ -269,6 +277,9 @@ void Analyzer::Display() { void Analyzer::PrepareData() { WPI_INFO(m_logger, "{}", "Preparing data"); try { + if (m_missingTests.size() > 0) { + throw sysid::MissingTestsError{m_missingTests}; + } m_manager->PrepareData(); UpdateFeedforwardGains(); UpdateFeedbackGains(); @@ -281,6 +292,9 @@ void Analyzer::PrepareData() { } catch (const sysid::NoDynamicDataError& e) { m_state = AnalyzerState::kTestDurationError; HandleError(e.what()); + } catch (const sysid::MissingTestsError& e) { + m_state = AnalyzerState::kMissingTestsError; + HandleError(e.what()); } catch (const AnalysisManager::FileReadingError& e) { m_state = AnalyzerState::kFileError; HandleError(e.what()); @@ -324,6 +338,10 @@ void Analyzer::HandleError(std::string_view msg) { PrepareRawGraphs(); } +void Analyzer::SetMissingTests(const std::vector& missingTests) { + m_missingTests = missingTests; +} + void Analyzer::DisplayGraphs() { ImGui::SetNextWindowPos(ImVec2{kDiagnosticPlotWindowPos}, ImGuiCond_FirstUseEver); diff --git a/sysid/src/main/native/cpp/view/DataSelector.cpp b/sysid/src/main/native/cpp/view/DataSelector.cpp index 17b2ab27e2..8f9648dc67 100644 --- a/sysid/src/main/native/cpp/view/DataSelector.cpp +++ b/sysid/src/main/native/cpp/view/DataSelector.cpp @@ -6,6 +6,7 @@ #include #include +#include #include #include @@ -112,6 +113,7 @@ void DataSelector::Display() { continue; } WPI_INFO(m_logger, "Loaded test state {}", it2->first); + m_executedTests.insert(it2->first); ++it2; } if (it->second.empty()) { @@ -133,6 +135,15 @@ void DataSelector::Display() { return; } + if (m_executedTests.size() < 4 && !m_testCountValidated) { + for (auto test : kValidTests) { + if (!m_executedTests.contains(test)) { + m_missingTests.push_back(test); + m_testCountValidated = true; + } + } + } + #if 0 // Test filtering if (ImGui::BeginCombo("Test", m_selectedTest.c_str())) { diff --git a/sysid/src/main/native/include/sysid/analysis/FilteringUtils.h b/sysid/src/main/native/include/sysid/analysis/FilteringUtils.h index 67266ae647..d14333800e 100644 --- a/sysid/src/main/native/include/sysid/analysis/FilteringUtils.h +++ b/sysid/src/main/native/include/sysid/analysis/FilteringUtils.h @@ -4,15 +4,16 @@ #pragma once -#include #include #include #include #include #include +#include #include #include +#include #include #include #include @@ -40,7 +41,7 @@ class InvalidDataError : public std::exception { */ explicit InvalidDataError(std::string_view message) { m_message = fmt::format( - "{}. Please verify that your units and data is reasonable and then " + "{} Please verify that your units and data is reasonable and then " "adjust your velocity threshold, test duration, and/or window size to " "try to fix this issue.", message); @@ -68,6 +69,25 @@ class NoQuasistaticDataError : public std::exception { } }; +/** + * Exception for not all tests being present. + */ +class MissingTestsError : public std::exception { + public: + explicit MissingTestsError(std::vector MissingTests) + : missingTests(std::move(MissingTests)) { + errorString = fmt::format( + "The following tests were not detected: {}. Make sure to perform all " + "four tests as described in the SysId documentation.", + fmt::join(missingTests, ", ")); + } + const char* what() const noexcept override { return errorString.c_str(); } + + private: + std::vector missingTests; + std::string errorString; +}; + /** * Exception for Dynamic Data being completely removed. */ diff --git a/sysid/src/main/native/include/sysid/view/Analyzer.h b/sysid/src/main/native/include/sysid/view/Analyzer.h index bb7763f26f..4b6e258341 100644 --- a/sysid/src/main/native/include/sysid/view/Analyzer.h +++ b/sysid/src/main/native/include/sysid/view/Analyzer.h @@ -8,6 +8,7 @@ #include #include #include +#include #include #include @@ -46,6 +47,7 @@ class Analyzer : public glass::View { kVelocityThresholdError, kTestDurationError, kGeneralDataError, + kMissingTestsError, kFileError }; /** @@ -91,6 +93,11 @@ class Analyzer : public glass::View { */ void AnalyzeData(); + /** + * Used by DataSelector to import any missing tests. + */ + void SetMissingTests(const std::vector& missingTests); + private: /** * Kills the data preparation thread @@ -199,6 +206,7 @@ class Analyzer : public glass::View { // Stores the exception message. std::string m_exception; + std::vector m_missingTests; bool m_calcDefaults = false; diff --git a/sysid/src/main/native/include/sysid/view/DataSelector.h b/sysid/src/main/native/include/sysid/view/DataSelector.h index 1020bc563a..85ed137650 100644 --- a/sysid/src/main/native/include/sysid/view/DataSelector.h +++ b/sysid/src/main/native/include/sysid/view/DataSelector.h @@ -7,6 +7,7 @@ #include #include #include +#include #include #include #include @@ -57,6 +58,7 @@ class DataSelector : public glass::View { * Called when new test data is loaded. */ std::function testdata; + std::vector m_missingTests; private: wpi::Logger& m_logger; @@ -76,6 +78,11 @@ class DataSelector : public glass::View { int m_selectedAnalysis = 0; std::future m_testdataFuture; std::vector m_testdataStats; + std::set kValidTests = {"quasistatic-forward", + "quasistatic-reverse", "dynamic-forward", + "dynamic-reverse"}; + std::set m_executedTests; + bool m_testCountValidated = false; static Tests LoadTests(const wpi::log::DataLogReaderEntry& testStateEntry); TestData BuildTestData(); diff --git a/upstream_utils/stack_walker.py b/upstream_utils/stack_walker.py deleted file mode 100755 index d0499d20c6..0000000000 --- a/upstream_utils/stack_walker.py +++ /dev/null @@ -1,65 +0,0 @@ -#!/usr/bin/env python3 - -import os -import shutil -import subprocess - -from upstream_utils import Lib - - -def crlf_to_lf(): - for root, _, files in os.walk("."): - if ".git" in root: - continue - - for fname in files: - filename = os.path.join(root, fname) - print(f"Converting CRLF -> LF for {filename}") - with open(filename, "rb") as f: - content = f.read() - content = content.replace(b"\r\n", b"\n") - - with open(filename, "wb") as f: - f.write(content) - - subprocess.check_call(["git", "add", "-A"]) - subprocess.check_call(["git", "commit", "-m", "Fix line endings"]) - - -def copy_upstream_src(wpilib_root): - wpiutil = os.path.join(wpilib_root, "wpiutil") - - shutil.copy( - os.path.join("Main", "StackWalker", "StackWalker.h"), - os.path.join(wpiutil, "src/main/native/windows/StackWalker.h"), - ) - - shutil.copy( - os.path.join("Main", "StackWalker", "StackWalker.cpp"), - os.path.join(wpiutil, "src/main/native/windows/StackWalker.cpp"), - ) - - -def main(): - name = "stack_walker" - url = "https://github.com/JochenKalmbach/StackWalker" - tag = "5b0df7a4db8896f6b6dc45d36e383c52577e3c6b" - - patch_options = { - "ignore_whitespace": True, - } - - stack_walker = Lib( - name, - url, - tag, - 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/stack_walker_patches/0001-Add-advapi-pragma.patch b/upstream_utils/stack_walker_patches/0001-Add-advapi-pragma.patch deleted file mode 100644 index 599a7120c4..0000000000 --- a/upstream_utils/stack_walker_patches/0001-Add-advapi-pragma.patch +++ /dev/null @@ -1,21 +0,0 @@ -From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 -From: Thad House -Date: Sat, 22 Jul 2023 13:03:13 -0700 -Subject: [PATCH] Add advapi pragma - ---- - Main/StackWalker/StackWalker.cpp | 1 + - 1 file changed, 1 insertion(+) - -diff --git a/Main/StackWalker/StackWalker.cpp b/Main/StackWalker/StackWalker.cpp -index 89545f8612d0d099d48fcf4184a2f2a30cf8577f..b2bcbaa447c5db1a3bcc155fb317ebc8a8050e79 100644 ---- a/Main/StackWalker/StackWalker.cpp -+++ b/Main/StackWalker/StackWalker.cpp -@@ -91,6 +91,7 @@ - #include - - #pragma comment(lib, "version.lib") // for "VerQueryValue" -+#pragma comment(lib, "Advapi32.lib") // for "GetUserName" - - #pragma warning(disable : 4826) - #if _MSC_VER >= 1900 diff --git a/wpilibNewCommands/src/generate/main/java/commandhid.java.jinja b/wpilibNewCommands/src/generate/main/java/commandhid.java.jinja index 331c7723a2..1198f6ae08 100644 --- a/wpilibNewCommands/src/generate/main/java/commandhid.java.jinja +++ b/wpilibNewCommands/src/generate/main/java/commandhid.java.jinja @@ -107,7 +107,7 @@ public class Command{{ ConsoleName }}Controller extends CommandGenericHID { {% endfor -%} {% for stick in sticks %} /** - * Get the {{ stick.NameParts[1] }} axis value of {{ stick.NameParts[0] }} side of the controller. + * Get the {{ stick.NameParts[1] }} axis value of {{ stick.NameParts[0] }} side of the controller. {{ stick.PositiveDirection }} is positive. * * @return The axis value. */ diff --git a/wpilibNewCommands/src/generate/main/native/include/frc2/command/button/commandhid.h.jinja b/wpilibNewCommands/src/generate/main/native/include/frc2/command/button/commandhid.h.jinja index 8e1d54074d..0a0242cc27 100644 --- a/wpilibNewCommands/src/generate/main/native/include/frc2/command/button/commandhid.h.jinja +++ b/wpilibNewCommands/src/generate/main/native/include/frc2/command/button/commandhid.h.jinja @@ -71,7 +71,7 @@ class Command{{ ConsoleName }}Controller : public CommandGenericHID { {% endfor -%} {% for stick in sticks %} /** - * Get the {{ stick.NameParts[1] }} axis value of {{ stick.NameParts[0] }} side of the controller. + * Get the {{ stick.NameParts[1] }} axis value of {{ stick.NameParts[0] }} side of the controller. {{ stick.PositiveDirection }} is positive. * * @return The axis value. */ diff --git a/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS4Controller.java b/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS4Controller.java index 9c72f60cbd..a65dbaea72 100644 --- a/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS4Controller.java +++ b/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS4Controller.java @@ -348,7 +348,7 @@ public class CommandPS4Controller extends CommandGenericHID { } /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ @@ -357,7 +357,7 @@ public class CommandPS4Controller extends CommandGenericHID { } /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ @@ -366,7 +366,7 @@ public class CommandPS4Controller extends CommandGenericHID { } /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ @@ -375,7 +375,7 @@ public class CommandPS4Controller extends CommandGenericHID { } /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS5Controller.java b/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS5Controller.java index 908d24e842..17f775a1ee 100644 --- a/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS5Controller.java +++ b/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS5Controller.java @@ -348,7 +348,7 @@ public class CommandPS5Controller extends CommandGenericHID { } /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ @@ -357,7 +357,7 @@ public class CommandPS5Controller extends CommandGenericHID { } /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ @@ -366,7 +366,7 @@ public class CommandPS5Controller extends CommandGenericHID { } /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ @@ -375,7 +375,7 @@ public class CommandPS5Controller extends CommandGenericHID { } /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandStadiaController.java b/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandStadiaController.java index 0890bbde48..a67fc877de 100644 --- a/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandStadiaController.java +++ b/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandStadiaController.java @@ -370,7 +370,7 @@ public class CommandStadiaController extends CommandGenericHID { } /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ @@ -379,7 +379,7 @@ public class CommandStadiaController extends CommandGenericHID { } /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ @@ -388,7 +388,7 @@ public class CommandStadiaController extends CommandGenericHID { } /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ @@ -397,7 +397,7 @@ public class CommandStadiaController extends CommandGenericHID { } /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandXboxController.java b/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandXboxController.java index a5ea65da28..a6de3c3e39 100644 --- a/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandXboxController.java +++ b/wpilibNewCommands/src/generated/main/java/edu/wpi/first/wpilibj2/command/button/CommandXboxController.java @@ -338,7 +338,7 @@ public class CommandXboxController extends CommandGenericHID { } /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ @@ -347,7 +347,7 @@ public class CommandXboxController extends CommandGenericHID { } /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ @@ -356,7 +356,7 @@ public class CommandXboxController extends CommandGenericHID { } /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ @@ -365,7 +365,7 @@ public class CommandXboxController extends CommandGenericHID { } /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandPS4Controller.h b/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandPS4Controller.h index ac0920f1a5..5e650aef29 100644 --- a/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandPS4Controller.h +++ b/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandPS4Controller.h @@ -204,28 +204,28 @@ class CommandPS4Controller : public CommandGenericHID { .GetDefaultButtonLoop()) const; /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ double GetLeftX() const; /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ double GetLeftY() const; /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ double GetRightX() const; /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandPS5Controller.h b/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandPS5Controller.h index a92693ea83..7aa66be6b8 100644 --- a/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandPS5Controller.h +++ b/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandPS5Controller.h @@ -204,28 +204,28 @@ class CommandPS5Controller : public CommandGenericHID { .GetDefaultButtonLoop()) const; /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ double GetLeftX() const; /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ double GetLeftY() const; /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ double GetRightX() const; /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandStadiaController.h b/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandStadiaController.h index cbd89c2ada..727b9a434f 100644 --- a/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandStadiaController.h +++ b/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandStadiaController.h @@ -216,28 +216,28 @@ class CommandStadiaController : public CommandGenericHID { .GetDefaultButtonLoop()) const; /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ double GetLeftX() const; /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ double GetRightX() const; /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ double GetLeftY() const; /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandXboxController.h b/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandXboxController.h index 9fb94f4825..f23d0a096a 100644 --- a/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandXboxController.h +++ b/wpilibNewCommands/src/generated/main/native/include/frc2/command/button/CommandXboxController.h @@ -190,28 +190,28 @@ class CommandXboxController : public CommandGenericHID { .GetDefaultButtonLoop()) const; /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ double GetLeftX() const; /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ double GetRightX() const; /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ double GetLeftY() const; /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandJoystick.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandJoystick.java index 647369f401..00d913e669 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandJoystick.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandJoystick.java @@ -173,6 +173,9 @@ public class CommandJoystick extends CommandGenericHID { /** * Get the x position of the HID. * + *

This depends on the mapping of the joystick connected to the current port. On most + * joysticks, positive is to the right. + * * @return the x position */ public double getX() { @@ -182,6 +185,9 @@ public class CommandJoystick extends CommandGenericHID { /** * Get the y position of the HID. * + *

This depends on the mapping of the joystick connected to the current port. On most + * joysticks, positive is to the back. + * * @return the y position */ public double getY() { @@ -218,8 +224,8 @@ public class CommandJoystick extends CommandGenericHID { } /** - * Get the magnitude of the direction vector formed by the joystick's current position relative to - * its origin. + * Get the magnitude of the vector formed by the joystick's current position relative to its + * origin. * * @return The magnitude of the direction vector */ @@ -228,16 +234,26 @@ public class CommandJoystick extends CommandGenericHID { } /** - * Get the direction of the vector formed by the joystick and its origin in radians. + * Get the direction of the vector formed by the joystick and its origin in radians. 0 is forward + * and clockwise is positive. (Straight right is π/2.) * * @return The direction of the vector in radians */ public double getDirectionRadians() { + // https://docs.wpilib.org/en/stable/docs/software/basic-programming/coordinate-system.html#joystick-and-controller-coordinate-system + // A positive rotation around the X axis moves the joystick right, and a + // positive rotation around the Y axis moves the joystick backward. When + // treating them as translations, 0 radians is measured from the right + // direction, and angle increases clockwise. + // + // It's rotated 90 degrees CCW (y is negated and the arguments are reversed) + // so that 0 radians is forward. return m_hid.getDirectionRadians(); } /** - * Get the direction of the vector formed by the joystick and its origin in degrees. + * Get the direction of the vector formed by the joystick and its origin in degrees. 0 is forward + * and clockwise is positive. (Straight right is 90.) * * @return The direction of the vector in degrees */ diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp index ae25fb05ea..2d36ef7cb6 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp @@ -26,5 +26,13 @@ double CommandJoystick::GetMagnitude() const { } units::radian_t CommandJoystick::GetDirection() const { + // https://docs.wpilib.org/en/stable/docs/software/basic-programming/coordinate-system.html#joystick-and-controller-coordinate-system + // A positive rotation around the X axis moves the joystick right, and a + // positive rotation around the Y axis moves the joystick backward. When + // treating them as translations, 0 radians is measured from the right + // direction, and angle increases clockwise. + // + // It's rotated 90 degrees CCW (y is negated and the arguments are reversed) + // so that 0 radians is forward. return m_hid.GetDirection(); } diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandJoystick.h b/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandJoystick.h index d1eeadfc2c..ee390d0aa5 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandJoystick.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandJoystick.h @@ -56,7 +56,7 @@ class CommandJoystick : public CommandGenericHID { class Trigger Top(frc::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** - * Get the magnitude of the direction vector formed by the joystick's + * Get the magnitude of the vector formed by the joystick's * current position relative to its origin. * * @return The magnitude of the direction vector @@ -64,7 +64,9 @@ class CommandJoystick : public CommandGenericHID { double GetMagnitude() const; /** - * Get the direction of the vector formed by the joystick and its origin. + * Get the direction of the vector formed by the joystick and its origin. 0 is + * forward and clockwise is positive. (Straight right is π/2 radians or 90 + * degrees.) * * @return The direction of the vector. */ diff --git a/wpilibc/src/generate/main/native/include/frc/hid.h.jinja b/wpilibc/src/generate/main/native/include/frc/hid.h.jinja index 5f26fe2435..af6d46d36c 100644 --- a/wpilibc/src/generate/main/native/include/frc/hid.h.jinja +++ b/wpilibc/src/generate/main/native/include/frc/hid.h.jinja @@ -47,7 +47,7 @@ class {{ ConsoleName }}Controller : public GenericHID, {{ ConsoleName }}Controller& operator=({{ ConsoleName }}Controller&&) = default; {% for stick in sticks %} /** - * Get the {{ stick.NameParts[1] }} axis value of {{ stick.NameParts[0] }} side of the controller. + * Get the {{ stick.NameParts[1] }} axis value of {{ stick.NameParts[0] }} side of the controller. {{ stick.PositiveDirection }} is positive. * * @return the axis value. */ diff --git a/wpilibc/src/generated/main/native/include/frc/PS4Controller.h b/wpilibc/src/generated/main/native/include/frc/PS4Controller.h index ed8f5a5cf2..01e8c49c47 100644 --- a/wpilibc/src/generated/main/native/include/frc/PS4Controller.h +++ b/wpilibc/src/generated/main/native/include/frc/PS4Controller.h @@ -45,28 +45,28 @@ class PS4Controller : public GenericHID, PS4Controller& operator=(PS4Controller&&) = default; /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return the axis value. */ double GetLeftX() const; /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return the axis value. */ double GetLeftY() const; /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return the axis value. */ double GetRightX() const; /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return the axis value. */ diff --git a/wpilibc/src/generated/main/native/include/frc/PS5Controller.h b/wpilibc/src/generated/main/native/include/frc/PS5Controller.h index 3a1c9217ee..2fd6557e25 100644 --- a/wpilibc/src/generated/main/native/include/frc/PS5Controller.h +++ b/wpilibc/src/generated/main/native/include/frc/PS5Controller.h @@ -45,28 +45,28 @@ class PS5Controller : public GenericHID, PS5Controller& operator=(PS5Controller&&) = default; /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return the axis value. */ double GetLeftX() const; /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return the axis value. */ double GetLeftY() const; /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return the axis value. */ double GetRightX() const; /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return the axis value. */ diff --git a/wpilibc/src/generated/main/native/include/frc/StadiaController.h b/wpilibc/src/generated/main/native/include/frc/StadiaController.h index 025377f600..89b7dab339 100644 --- a/wpilibc/src/generated/main/native/include/frc/StadiaController.h +++ b/wpilibc/src/generated/main/native/include/frc/StadiaController.h @@ -45,28 +45,28 @@ class StadiaController : public GenericHID, StadiaController& operator=(StadiaController&&) = default; /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return the axis value. */ double GetLeftX() const; /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return the axis value. */ double GetRightX() const; /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return the axis value. */ double GetLeftY() const; /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return the axis value. */ diff --git a/wpilibc/src/generated/main/native/include/frc/XboxController.h b/wpilibc/src/generated/main/native/include/frc/XboxController.h index 222fc2b0f8..e69f9bdb02 100644 --- a/wpilibc/src/generated/main/native/include/frc/XboxController.h +++ b/wpilibc/src/generated/main/native/include/frc/XboxController.h @@ -45,28 +45,28 @@ class XboxController : public GenericHID, XboxController& operator=(XboxController&&) = default; /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return the axis value. */ double GetLeftX() const; /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return the axis value. */ double GetRightX() const; /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return the axis value. */ double GetLeftY() const; /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return the axis value. */ diff --git a/wpilibc/src/main/native/cpp/AddressableLED.cpp b/wpilibc/src/main/native/cpp/AddressableLED.cpp index d700d18f6d..b437eb2f2e 100644 --- a/wpilibc/src/main/native/cpp/AddressableLED.cpp +++ b/wpilibc/src/main/native/cpp/AddressableLED.cpp @@ -34,6 +34,13 @@ AddressableLED::AddressableLED(int port) : m_port{port} { HAL_ReportUsage("IO", port, "AddressableLED"); } +void AddressableLED::SetColorOrder(AddressableLED::ColorOrder order) { + int32_t status = 0; + HAL_SetAddressableLEDColorOrder( + m_handle, static_cast(order), &status); + FRC_CheckErrorStatus(status, "Port {} Color order {}", m_port, order); +} + void AddressableLED::SetLength(int length) { int32_t status = 0; HAL_SetAddressableLEDLength(m_handle, length, &status); diff --git a/wpilibc/src/main/native/cpp/Alert.cpp b/wpilibc/src/main/native/cpp/Alert.cpp index 17fa52f4ea..7cce523377 100644 --- a/wpilibc/src/main/native/cpp/Alert.cpp +++ b/wpilibc/src/main/native/cpp/Alert.cpp @@ -82,17 +82,18 @@ class Alert::SendableAlerts : public nt::NTSendable, * @return the SendableAlerts for the group */ static SendableAlerts& ForGroup(std::string_view group) { - // Force initialization of SendableRegistry before our magic static to - // prevent incorrect destruction order. - wpi::SendableRegistry::EnsureInitialized(); - static wpi::StringMap groups; - - auto [iter, exists] = groups.try_emplace(group); - SendableAlerts& sendable = iter->second; - if (!exists) { - frc::SmartDashboard::PutData(group, &iter->second); + SendableAlerts* salert = nullptr; + try { + auto* sendable = frc::SmartDashboard::GetData(group); + salert = dynamic_cast(sendable); + } catch (frc::RuntimeError&) { } - return sendable; + if (!salert) { + // this leaks if ResetSmartDashboardInstance is called, but that's fine + salert = new Alert::SendableAlerts; + frc::SmartDashboard::PutData(group, salert); + } + return *salert; } private: diff --git a/wpilibc/src/main/native/cpp/Joystick.cpp b/wpilibc/src/main/native/cpp/Joystick.cpp index 7b9ed18127..4e98b3861c 100644 --- a/wpilibc/src/main/native/cpp/Joystick.cpp +++ b/wpilibc/src/main/native/cpp/Joystick.cpp @@ -119,5 +119,13 @@ double Joystick::GetMagnitude() const { } units::radian_t Joystick::GetDirection() const { + // https://docs.wpilib.org/en/stable/docs/software/basic-programming/coordinate-system.html#joystick-and-controller-coordinate-system + // A positive rotation around the X axis moves the joystick right, and a + // positive rotation around the Y axis moves the joystick backward. When + // treating them as translations, 0 radians is measured from the right + // direction, and angle increases clockwise. + // + // It's rotated 90 degrees CCW (y is negated and the arguments are reversed) + // so that 0 radians is forward. return units::radian_t{std::atan2(GetX(), -GetY())}; } diff --git a/wpilibc/src/main/native/include/frc/AddressableLED.h b/wpilibc/src/main/native/include/frc/AddressableLED.h index d7e7ca40a5..c4aa7e9b4a 100644 --- a/wpilibc/src/main/native/include/frc/AddressableLED.h +++ b/wpilibc/src/main/native/include/frc/AddressableLED.h @@ -24,12 +24,27 @@ namespace frc { * By default, the timing supports WS2812B and WS2815 LEDs, but is configurable * using SetBitTiming() * + * Some LEDs use a different color order than the default GRB. The color order + * is configurable using SetColorOrder(). + * *

Only 1 LED driver is currently supported by the roboRIO. However, * multiple LED strips can be connected in series and controlled from the * single driver. */ class AddressableLED { public: + /** + * Order that color data is sent over the wire. + */ + enum ColorOrder { + kRGB = HAL_ALED_RGB, ///< RGB order + kRBG = HAL_ALED_RBG, ///< RBG order + kBGR = HAL_ALED_BGR, ///< BGR order + kBRG = HAL_ALED_BRG, ///< BRG order + kGBR = HAL_ALED_GBR, ///< GBR order + kGRB = HAL_ALED_GRB ///< GRB order. This is the default order. + }; + class LEDData : public HAL_AddressableLEDData { public: LEDData() : LEDData(0, 0, 0) {} @@ -95,6 +110,15 @@ class AddressableLED { AddressableLED(AddressableLED&&) = default; AddressableLED& operator=(AddressableLED&&) = default; + /** + * Sets the color order for this AddressableLED. The default order is GRB. + * + * This will take effect on the next call to SetData(). + * + * @param order the color order + */ + void SetColorOrder(ColorOrder order); + /** * Sets the length of the LED strip. * @@ -169,4 +193,9 @@ class AddressableLED { hal::Handle m_handle; int m_port; }; + +constexpr auto format_as(AddressableLED::ColorOrder order) { + return static_cast(order); +} + } // namespace frc diff --git a/wpilibc/src/main/native/include/frc/Joystick.h b/wpilibc/src/main/native/include/frc/Joystick.h index 0f8e101491..399a304d84 100644 --- a/wpilibc/src/main/native/include/frc/Joystick.h +++ b/wpilibc/src/main/native/include/frc/Joystick.h @@ -148,6 +148,7 @@ class Joystick : public GenericHID { * Get the X value of the current joystick. * * This depends on the mapping of the joystick connected to the current port. + * On most joysticks, positive is to the right. */ double GetX() const; @@ -155,6 +156,7 @@ class Joystick : public GenericHID { * Get the Y value of the current joystick. * * This depends on the mapping of the joystick connected to the current port. + * On most joysticks, positive is to the back. */ double GetY() const; @@ -244,7 +246,7 @@ class Joystick : public GenericHID { BooleanEvent Top(EventLoop* loop) const; /** - * Get the magnitude of the direction vector formed by the joystick's + * Get the magnitude of the vector formed by the joystick's * current position relative to its origin. * * @return The magnitude of the direction vector @@ -252,7 +254,9 @@ class Joystick : public GenericHID { double GetMagnitude() const; /** - * Get the direction of the vector formed by the joystick and its origin. + * Get the direction of the vector formed by the joystick and its origin. 0 is + * forward and clockwise is positive. (Straight right is π/2 radians or 90 + * degrees.) * * @return The direction of the vector. */ diff --git a/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h b/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h index 788d5ceeed..8747a0d18c 100644 --- a/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h @@ -52,11 +52,11 @@ class LinearSystemSim { * @param dt The time between updates. */ void Update(units::second_t dt) { - // Update x. By default, this is the linear system dynamics x_k+1 = Ax_k + - // Bu_k + // Update x. By default, this is the linear system dynamics xₖ₊₁ = Axₖ + + // Buₖ. m_x = UpdateX(m_x, m_u, dt); - // y = Cx + Du + // yₖ = Cxₖ + Duₖ m_y = m_plant.CalculateY(m_x, m_u); // Add noise. If the user did not pass a noise vector to the @@ -115,7 +115,14 @@ class LinearSystemSim { * * @param state The new state. */ - void SetState(const Vectord& state) { m_x = state; } + void SetState(const Vectord& state) { + m_x = state; + + // Update the output to reflect the new state. + // + // yₖ = Cxₖ + Duₖ + m_y = m_plant.CalculateY(m_x, m_u); + } protected: /** diff --git a/wpilibc/src/test/native/cpp/AlertTest.cpp b/wpilibc/src/test/native/cpp/AlertTest.cpp index a02e0166a8..b19f0dd0c4 100644 --- a/wpilibc/src/test/native/cpp/AlertTest.cpp +++ b/wpilibc/src/test/native/cpp/AlertTest.cpp @@ -33,8 +33,7 @@ class AlertsTest : public ::testing::Test { std::string GetGroupName() { const ::testing::TestInfo* testInfo = ::testing::UnitTest::GetInstance()->current_test_info(); - return fmt::format("{}_{}", testInfo->test_suite_name(), - testInfo->test_case_name()); + return fmt::format("{}_{}", testInfo->test_suite_name(), testInfo->name()); } template @@ -80,7 +79,16 @@ class AlertsTest : public ::testing::Test { #define EXPECT_STATE(type, ...) \ EXPECT_EQ(GetActiveAlerts(type), (std::vector{__VA_ARGS__})) -TEST_F(AlertsTest, SetUnset) { +TEST_F(AlertsTest, SetUnsetSingle) { + auto one = MakeAlert("one", kInfo); + EXPECT_FALSE(IsAlertActive("one", kInfo)); + one.Set(true); + EXPECT_TRUE(IsAlertActive("one", kInfo)); + one.Set(false); + EXPECT_FALSE(IsAlertActive("one", kInfo)); +} + +TEST_F(AlertsTest, SetUnsetMultiple) { auto one = MakeAlert("one", kError); auto two = MakeAlert("two", kInfo); EXPECT_FALSE(IsAlertActive("one", kError)); diff --git a/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp index dd835650cd..2777ee48c0 100644 --- a/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp @@ -44,6 +44,15 @@ TEST(ElevatorSimTest, StateSpaceSim) { EXPECT_NEAR(controller.GetSetpoint(), sim.GetPosition().value(), 0.2); } +TEST(ElevatorSimTest, InitialState) { + constexpr auto startingHeight = 0.5_m; + frc::sim::ElevatorSim sim(frc::DCMotor::KrakenX60(2), 20, 8_kg, 0.1_m, 0_m, + 1_m, true, startingHeight, {0.01, 0.0}); + + EXPECT_DOUBLE_EQ(startingHeight.value(), sim.GetPosition().value()); + EXPECT_DOUBLE_EQ(0, sim.GetVelocity().value()); +} + TEST(ElevatorSimTest, MinMax) { frc::sim::ElevatorSim sim(frc::DCMotor::Vex775Pro(4), 14.67, 8_kg, 0.75_in, 0_m, 1_m, true, 0_m, {0.01}); diff --git a/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp index 1311a0ebf6..3f6a1446ce 100644 --- a/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp @@ -21,3 +21,12 @@ TEST(SingleJointedArmTest, Disabled) { // The arm should swing down. EXPECT_NEAR(sim.GetAngle().value(), -std::numbers::pi / 2, 0.01); } + +TEST(SingleJointedArmTest, InitialState) { + constexpr auto startingAngle = 45_deg; + frc::sim::SingleJointedArmSim sim(frc::DCMotor::KrakenX60(2), 125, 3_kg_sq_m, + 30_in, 0_deg, 90_deg, true, startingAngle); + + EXPECT_EQ(startingAngle, sim.GetAngle()); + EXPECT_DOUBLE_EQ(0, sim.GetVelocity().value()); +} diff --git a/wpilibj/src/generate/hids.json b/wpilibj/src/generate/hids.json index 1c58a9597f..2b8baaf921 100644 --- a/wpilibj/src/generate/hids.json +++ b/wpilibj/src/generate/hids.json @@ -59,28 +59,32 @@ "left", "X" ], - "value": 0 + "value": 0, + "PositiveDirection": "Right" }, { "NameParts": [ "right", "X" ], - "value": 4 + "value": 4, + "PositiveDirection": "Right" }, { "NameParts": [ "left", "Y" ], - "value": 1 + "value": 1, + "PositiveDirection": "Back" }, { "NameParts": [ "right", "Y" ], - "value": 5 + "value": 5, + "PositiveDirection": "Back" } ], "triggers": [ @@ -173,28 +177,32 @@ "left", "X" ], - "value": 0 + "value": 0, + "PositiveDirection": "Right" }, { "NameParts": [ "left", "Y" ], - "value": 1 + "value": 1, + "PositiveDirection": "Back" }, { "NameParts": [ "right", "X" ], - "value": 2 + "value": 2, + "PositiveDirection": "Right" }, { "NameParts": [ "right", "Y" ], - "value": 5 + "value": 5, + "PositiveDirection": "Back" } ], "triggers": [ @@ -287,28 +295,32 @@ "left", "X" ], - "value": 0 + "value": 0, + "PositiveDirection": "Right" }, { "NameParts": [ "left", "Y" ], - "value": 1 + "value": 1, + "PositiveDirection": "Back" }, { "NameParts": [ "right", "X" ], - "value": 2 + "value": 2, + "PositiveDirection": "Right" }, { "NameParts": [ "right", "Y" ], - "value": 5 + "value": 5, + "PositiveDirection": "Back" } ], "triggers": [ @@ -408,28 +420,32 @@ "left", "X" ], - "value": 0 + "value": 0, + "PositiveDirection": "Right" }, { "NameParts": [ "right", "X" ], - "value": 3 + "value": 3, + "PositiveDirection": "Right" }, { "NameParts": [ "left", "Y" ], - "value": 1 + "value": 1, + "PositiveDirection": "Back" }, { "NameParts": [ "right", "Y" ], - "value": 4 + "value": 4, + "PositiveDirection": "Back" } ] } diff --git a/wpilibj/src/generate/hids.schema.json b/wpilibj/src/generate/hids.schema.json index df9e946176..6f81c7c390 100644 --- a/wpilibj/src/generate/hids.schema.json +++ b/wpilibj/src/generate/hids.schema.json @@ -62,7 +62,8 @@ "type": "object", "required": [ "NameParts", - "value" + "value", + "PositiveDirection" ], "properties": { "NameParts": { @@ -76,6 +77,10 @@ "value": { "description": "The axis value", "type": "integer" + }, + "PositiveDirection": { + "description": "The positive direction of the axis.", + "type": "string" } } } diff --git a/wpilibj/src/generate/main/java/hid.java.jinja b/wpilibj/src/generate/main/java/hid.java.jinja index 8fed2a6272..218993e98b 100644 --- a/wpilibj/src/generate/main/java/hid.java.jinja +++ b/wpilibj/src/generate/main/java/hid.java.jinja @@ -102,7 +102,7 @@ public class {{ ConsoleName }}Controller extends GenericHID implements Sendable } {% for stick in sticks %} /** - * Get the {{ stick.NameParts[1] }} axis value of {{ stick.NameParts[0] }} side of the controller. + * Get the {{ stick.NameParts[1] }} axis value of {{ stick.NameParts[0] }} side of the controller. {{ stick.PositiveDirection }} is positive. * * @return The axis value. */ diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java index 298d3f1419..fd69148e19 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java @@ -128,7 +128,7 @@ public class PS4Controller extends GenericHID implements Sendable { } /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ @@ -137,7 +137,7 @@ public class PS4Controller extends GenericHID implements Sendable { } /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ @@ -146,7 +146,7 @@ public class PS4Controller extends GenericHID implements Sendable { } /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ @@ -155,7 +155,7 @@ public class PS4Controller extends GenericHID implements Sendable { } /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java index bcb7bf2f2d..a9f9716f28 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java @@ -128,7 +128,7 @@ public class PS5Controller extends GenericHID implements Sendable { } /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ @@ -137,7 +137,7 @@ public class PS5Controller extends GenericHID implements Sendable { } /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ @@ -146,7 +146,7 @@ public class PS5Controller extends GenericHID implements Sendable { } /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ @@ -155,7 +155,7 @@ public class PS5Controller extends GenericHID implements Sendable { } /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java index 18e2fe46ae..7dd1afed32 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java @@ -126,7 +126,7 @@ public class StadiaController extends GenericHID implements Sendable { } /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ @@ -135,7 +135,7 @@ public class StadiaController extends GenericHID implements Sendable { } /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ @@ -144,7 +144,7 @@ public class StadiaController extends GenericHID implements Sendable { } /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ @@ -153,7 +153,7 @@ public class StadiaController extends GenericHID implements Sendable { } /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java index a575f2f5c2..2016f7b9e1 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java @@ -120,7 +120,7 @@ public class XboxController extends GenericHID implements Sendable { } /** - * Get the X axis value of left side of the controller. + * Get the X axis value of left side of the controller. Right is positive. * * @return The axis value. */ @@ -129,7 +129,7 @@ public class XboxController extends GenericHID implements Sendable { } /** - * Get the X axis value of right side of the controller. + * Get the X axis value of right side of the controller. Right is positive. * * @return The axis value. */ @@ -138,7 +138,7 @@ public class XboxController extends GenericHID implements Sendable { } /** - * Get the Y axis value of left side of the controller. + * Get the Y axis value of left side of the controller. Back is positive. * * @return The axis value. */ @@ -147,7 +147,7 @@ public class XboxController extends GenericHID implements Sendable { } /** - * Get the Y axis value of right side of the controller. + * Get the Y axis value of right side of the controller. Back is positive. * * @return The axis value. */ diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java index 09ecb3b28c..3e786783ef 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java @@ -11,13 +11,57 @@ import edu.wpi.first.hal.PWMJNI; /** * A class for driving addressable LEDs, such as WS2812B, WS2815, and NeoPixels. * - *

By default, the timing supports WS2812B and WS2815 LEDs, but is configurable using - * setBitTiming() + *

By default, the timing supports WS2812B and WS2815 LEDs, but is configurable using {@link + * #setBitTiming(int, int, int, int)} + * + *

Some LEDs use a different color order than the default GRB. The color order is configurable + * using {@link #setColorOrder(ColorOrder)}. * *

Only 1 LED driver is currently supported by the roboRIO. However, multiple LED strips can be * connected in series and controlled from the single driver. */ public class AddressableLED implements AutoCloseable { + /** Order that color data is sent over the wire. */ + public enum ColorOrder { + /** RGB order. */ + kRGB(AddressableLEDJNI.COLOR_ORDER_RGB), + /** RBG order. */ + kRBG(AddressableLEDJNI.COLOR_ORDER_RBG), + /** BGR order. */ + kBGR(AddressableLEDJNI.COLOR_ORDER_BGR), + /** BRG order. */ + kBRG(AddressableLEDJNI.COLOR_ORDER_BRG), + /** GBR order. */ + kGBR(AddressableLEDJNI.COLOR_ORDER_GBR), + /** GRB order. This is the default order. */ + kGRB(AddressableLEDJNI.COLOR_ORDER_GRB); + + /** The native value for this ColorOrder. */ + public final int value; + + ColorOrder(int value) { + this.value = value; + } + + /** + * Gets a color order from an int value. + * + * @param value int value + * @return color order + */ + public ColorOrder fromValue(int value) { + return switch (value) { + case AddressableLEDJNI.COLOR_ORDER_RBG -> kRBG; + case AddressableLEDJNI.COLOR_ORDER_BGR -> kBGR; + case AddressableLEDJNI.COLOR_ORDER_BRG -> kBRG; + case AddressableLEDJNI.COLOR_ORDER_GRB -> kGRB; + case AddressableLEDJNI.COLOR_ORDER_GBR -> kGBR; + case AddressableLEDJNI.COLOR_ORDER_RGB -> kRGB; + default -> kGRB; + }; + } + } + private final int m_pwmHandle; private final int m_handle; @@ -42,6 +86,17 @@ public class AddressableLED implements AutoCloseable { } } + /** + * Sets the color order for this AddressableLED. The default order is GRB. + * + *

This will take effect on the next call to {@link #setData(AddressableLEDBuffer)}. + * + * @param order the color order + */ + public void setColorOrder(ColorOrder order) { + AddressableLEDJNI.setColorOrder(m_handle, order.value); + } + /** * Sets the length of the LED strip. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java index 9e54904310..44cf56d946 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java @@ -178,7 +178,7 @@ public class Joystick extends GenericHID { /** * Get the X value of the joystick. This depends on the mapping of the joystick connected to the - * current port. + * current port. On most joysticks, positive is to the right. * * @return The X value of the joystick. */ @@ -188,7 +188,7 @@ public class Joystick extends GenericHID { /** * Get the Y value of the joystick. This depends on the mapping of the joystick connected to the - * current port. + * current port. On most joysticks, positive is to the back. * * @return The Y value of the joystick. */ @@ -302,8 +302,8 @@ public class Joystick extends GenericHID { } /** - * Get the magnitude of the direction vector formed by the joystick's current position relative to - * its origin. + * Get the magnitude of the vector formed by the joystick's current position relative to its + * origin. * * @return The magnitude of the direction vector */ @@ -312,16 +312,26 @@ public class Joystick extends GenericHID { } /** - * Get the direction of the vector formed by the joystick and its origin in radians. + * Get the direction of the vector formed by the joystick and its origin in radians. 0 is forward + * and clockwise is positive. (Straight right is π/2.) * * @return The direction of the vector in radians */ public double getDirectionRadians() { + // https://docs.wpilib.org/en/stable/docs/software/basic-programming/coordinate-system.html#joystick-and-controller-coordinate-system + // A positive rotation around the X axis moves the joystick right, and a + // positive rotation around the Y axis moves the joystick backward. When + // treating them as translations, 0 radians is measured from the right + // direction, and angle increases clockwise. + // + // It's rotated 90 degrees CCW (y is negated and the arguments are reversed) + // so that 0 radians is forward. return Math.atan2(getX(), -getY()); } /** - * Get the direction of the vector formed by the joystick and its origin in degrees. + * Get the direction of the vector formed by the joystick and its origin in degrees. 0 is forward + * and clockwise is positive. (Straight right is 90.) * * @return The direction of the vector in degrees */ diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java index 87ecdae577..99620daa79 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java @@ -75,10 +75,10 @@ public class LinearSystemSim state) { m_x = state; + + // Update the output to reflect the new state. + // + // yₖ = Cxₖ + Duₖ + m_y = m_plant.calculateY(m_x, m_u); } /** diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/AlertTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/AlertTest.java index 3e1f9b3abd..79e4bb0f88 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/AlertTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/AlertTest.java @@ -81,7 +81,18 @@ class AlertTest { } @Test - void setUnset() { + void setUnsetSingle() { + try (var one = makeAlert("one", AlertType.kInfo)) { + assertFalse(isAlertActive("one", AlertType.kInfo)); + one.set(true); + assertTrue(isAlertActive("one", AlertType.kInfo)); + one.set(false); + assertFalse(isAlertActive("one", AlertType.kInfo)); + } + } + + @Test + void setUnsetMultiple() { try (var one = makeAlert("one", AlertType.kError); var two = makeAlert("two", AlertType.kInfo)) { assertFalse(isAlertActive("one", AlertType.kError)); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java index 260bc2772a..aa49dcbbc7 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java @@ -63,6 +63,17 @@ class ElevatorSimTest { } } + @Test + void testInitialState() { + double startingHeightMeters = 0.5; + var sim = + new ElevatorSim( + DCMotor.getKrakenX60(2), 20, 8.0, 0.1, 0.0, 1.0, true, startingHeightMeters, 0.01, 0.0); + + assertEquals(startingHeightMeters, sim.getPosition()); + assertEquals(0, sim.getVelocity()); + } + @Test void testMinMax() { var sim = diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSimTest.java index 4cbd7db4fb..0842119d7e 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSimTest.java @@ -12,28 +12,46 @@ import edu.wpi.first.math.util.Units; import org.junit.jupiter.api.Test; class SingleJointedArmSimTest { - SingleJointedArmSim m_sim = - new SingleJointedArmSim( - DCMotor.getVex775Pro(2), - 300, - 3.0, - Units.inchesToMeters(30.0), - -Math.PI, - 0.0, - true, - Math.PI / 2.0); - @Test void testArmDisabled() { + SingleJointedArmSim sim = + new SingleJointedArmSim( + DCMotor.getVex775Pro(2), + 300, + 3.0, + Units.inchesToMeters(30.0), + -Math.PI, + 0.0, + true, + Math.PI / 2.0); + // Reset Arm angle to 0 - m_sim.setState(VecBuilder.fill(0.0, 0.0)); + sim.setState(VecBuilder.fill(0.0, 0.0)); for (int i = 0; i < 12 / 0.02; i++) { - m_sim.setInput(0.0); - m_sim.update(0.020); + sim.setInput(0.0); + sim.update(0.020); } // the arm should swing down - assertEquals(-Math.PI / 2.0, m_sim.getAngle(), 0.1); + assertEquals(-Math.PI / 2.0, sim.getAngle(), 0.1); + } + + @Test + void testInitialState() { + double startingAngleRads = Math.PI / 4.0; + SingleJointedArmSim sim = + new SingleJointedArmSim( + DCMotor.getKrakenX60(2), + 125, + 3.0, + Units.inchesToMeters(30.0), + 0, + Math.PI / 2.0, + true, + startingAngleRads); + + assertEquals(startingAngleRads, sim.getAngle()); + assertEquals(0, sim.getVelocity()); } } diff --git a/wpimath/CMakeLists.txt b/wpimath/CMakeLists.txt index 19780acd83..348fef5e99 100644 --- a/wpimath/CMakeLists.txt +++ b/wpimath/CMakeLists.txt @@ -189,6 +189,12 @@ target_include_directories( $ ) +install( + DIRECTORY src/generated/main/native/cpp/ + DESTINATION "${include_dest}/wpimath" + FILES_MATCHING + PATTERN "*.h" +) install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpimath") target_include_directories( wpimath diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java index d406819a99..91ebab06c2 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java @@ -16,16 +16,16 @@ import edu.wpi.first.util.struct.StructSerializable; */ public class ArmFeedforward implements ProtobufSerializable, StructSerializable { /** The static gain, in volts. */ - private final double ks; + private double ks; /** The gravity gain, in volts. */ - private final double kg; + private double kg; /** The velocity gain, in V/(rad/s). */ - private final double kv; + private double kv; /** The acceleration gain, in V/(rad/s²). */ - private final double ka; + private double ka; /** The period, in seconds. */ private final double m_dt; @@ -85,6 +85,42 @@ public class ArmFeedforward implements ProtobufSerializable, StructSerializable this(ks, kg, kv, 0); } + /** + * Sets the static gain. + * + * @param ks The static gain in volts. + */ + public void setKs(double ks) { + this.ks = ks; + } + + /** + * Sets the gravity gain. + * + * @param kg The gravity gain in volts. + */ + public void setKg(double kg) { + this.kg = kg; + } + + /** + * Sets the velocity gain. + * + * @param kv The velocity gain in V/(rad/s). + */ + public void setKv(double kv) { + this.kv = kv; + } + + /** + * Sets the acceleration gain. + * + * @param ka The acceleration gain in V/(rad/s²). + */ + public void setKa(double ka) { + this.ka = ka; + } + /** * Returns the static gain in volts. * diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java index 0702af3f63..9966437f5b 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java @@ -15,16 +15,16 @@ import edu.wpi.first.util.struct.StructSerializable; */ public class ElevatorFeedforward implements ProtobufSerializable, StructSerializable { /** The static gain, in volts. */ - private final double ks; + private double ks; /** The gravity gain, in volts. */ - private final double kg; + private double kg; /** The velocity gain, in V/(m/s). */ - private final double kv; + private double kv; /** The acceleration gain, in V/(m/s²). */ - private final double ka; + private double ka; /** The period, in seconds. */ private final double m_dt; @@ -85,6 +85,42 @@ public class ElevatorFeedforward implements ProtobufSerializable, StructSerializ this(ks, kg, kv, 0); } + /** + * Sets the static gain. + * + * @param ks The static gain in volts. + */ + public void setKs(double ks) { + this.ks = ks; + } + + /** + * Sets the gravity gain. + * + * @param kg The gravity gain in volts. + */ + public void setKg(double kg) { + this.kg = kg; + } + + /** + * Sets the velocity gain. + * + * @param kv The velocity gain in V/(m/s). + */ + public void setKv(double kv) { + this.kv = kv; + } + + /** + * Sets the acceleration gain. + * + * @param ka The acceleration gain in V/(m/s²). + */ + public void setKa(double ka) { + this.ka = ka; + } + /** * Returns the static gain in volts. * 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 d4b211602b..f5c9df7e7a 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 @@ -12,13 +12,13 @@ import edu.wpi.first.util.struct.StructSerializable; /** A helper class that computes feedforward outputs for a simple permanent-magnet DC motor. */ public class SimpleMotorFeedforward implements ProtobufSerializable, StructSerializable { /** The static gain, in volts. */ - private final double ks; + private double ks; /** The velocity gain, in V/(units/s). */ - private final double kv; + private double kv; /** The acceleration gain, in V/(units/s²). */ - private final double ka; + private double ka; /** The period, in seconds. */ private final double m_dt; @@ -82,6 +82,33 @@ public class SimpleMotorFeedforward implements ProtobufSerializable, StructSeria this(ks, kv, 0); } + /** + * Sets the static gain. + * + * @param ks The static gain in volts. + */ + public void setKs(double ks) { + this.ks = ks; + } + + /** + * Sets the velocity gain. + * + * @param kv The velocity gain in V/(units/s). + */ + public void setKv(double kv) { + this.kv = kv; + } + + /** + * Sets the acceleration gain. + * + * @param ka The acceleration gain in V/(units/s²). + */ + public void setKa(double ka) { + this.ka = ka; + } + /** * Returns the static gain in volts. * diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java index 00fd90c3a1..9de9d528f7 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java @@ -90,7 +90,10 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable { * along the y-axis, and omega * dt around the z-axis). * *

This is useful for compensating for translational skew when translating and rotating a - * swerve drivetrain. + * holonomic (swerve or mecanum) drivetrain. However, scaling down the ChassisSpeeds after + * discretizing (e.g., when desaturating swerve module speeds) rotates the direction of net motion + * in the opposite direction of rotational velocity, introducing a different translational skew + * which is not accounted for by discretization. * * @param dt The duration of the timestep in seconds the speeds should be applied for. * @return Discretized ChassisSpeeds. diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java index 915ad68fd3..2e69777af8 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java @@ -257,6 +257,10 @@ public class SwerveDriveKinematics * reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the * absolute threshold, while maintaining the ratio of speeds between modules. * + *

Scaling down the module speeds rotates the direction of net motion in the opposite direction + * of rotational velocity, which makes discretizing the chassis speeds inaccurate because the + * discretization did not account for this translational skew. + * * @param moduleStates Reference to array of module states. The array will be mutated with the * normalized speeds! * @param attainableMaxSpeed The absolute max speed in meters per second that a module can reach. @@ -282,6 +286,10 @@ public class SwerveDriveKinematics * reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the * absolute threshold, while maintaining the ratio of speeds between modules. * + *

Scaling down the module speeds rotates the direction of net motion in the opposite direction + * of rotational velocity, which makes discretizing the chassis speeds inaccurate because the + * discretization did not account for this translational skew. + * * @param moduleStates Reference to array of module states. The array will be mutated with the * normalized speeds! * @param attainableMaxSpeed The absolute max speed in meters per second that a module can reach. @@ -300,6 +308,10 @@ public class SwerveDriveKinematics * reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the * absolute threshold, while maintaining the ratio of speeds between modules. * + *

Scaling down the module speeds rotates the direction of net motion in the opposite direction + * of rotational velocity, which makes discretizing the chassis speeds inaccurate because the + * discretization did not account for this translational skew. + * * @param moduleStates Reference to array of module states. The array will be mutated with the * normalized speeds! * @param desiredChassisSpeed The desired speed of the robot @@ -346,6 +358,10 @@ public class SwerveDriveKinematics * reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the * absolute threshold, while maintaining the ratio of speeds between modules. * + *

Scaling down the module speeds rotates the direction of net motion in the opposite direction + * of rotational velocity, which makes discretizing the chassis speeds inaccurate because the + * discretization did not account for this translational skew. + * * @param moduleStates Reference to array of module states. The array will be mutated with the * normalized speeds! * @param desiredChassisSpeed The desired speed of the robot diff --git a/wpimath/src/main/native/cpp/controller/ArmFeedforward.cpp b/wpimath/src/main/native/cpp/controller/ArmFeedforward.cpp index 7c9c44609d..df1f89d984 100644 --- a/wpimath/src/main/native/cpp/controller/ArmFeedforward.cpp +++ b/wpimath/src/main/native/cpp/controller/ArmFeedforward.cpp @@ -20,6 +20,13 @@ units::volt_t ArmFeedforward::Calculate( units::unit_t nextVelocity) const { using VarMat = sleipnir::VariableMatrix; + // Small kₐ values make the solver ill-conditioned + if (kA < units::unit_t{1e-1}) { + auto acceleration = (nextVelocity - currentVelocity) / m_dt; + return kS * wpi::sgn(currentVelocity.value()) + kV * currentVelocity + + kA * acceleration + kG * units::math::cos(currentAngle); + } + // Arm dynamics Matrixd<2, 2> A{{0.0, 1.0}, {0.0, -kV.value() / kA.value()}}; Matrixd<2, 1> B{{0.0}, {1.0 / kA.value()}}; diff --git a/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h b/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h index ace4b9c06f..d6bdc0f81c 100644 --- a/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h +++ b/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h @@ -4,6 +4,8 @@ #pragma once +#include + #include #include @@ -242,6 +244,34 @@ class WPILIB_DLLEXPORT ArmFeedforward { return MaxAchievableAcceleration(-maxVoltage, angle, velocity); } + /** + * Sets the static gain. + * + * @param kS The static gain. + */ + constexpr void SetKs(units::volt_t kS) { this->kS = kS; } + + /** + * Sets the gravity gain. + * + * @param kG The gravity gain. + */ + constexpr void SetKg(units::volt_t kG) { this->kG = kG; } + + /** + * Sets the velocity gain. + * + * @param kV The velocity gain. + */ + constexpr void SetKv(units::unit_t kV) { this->kV = kV; } + + /** + * Sets the acceleration gain. + * + * @param kA The acceleration gain. + */ + constexpr void SetKa(units::unit_t kA) { this->kA = kA; } + /** * Returns the static gain. * diff --git a/wpimath/src/main/native/include/frc/controller/ElevatorFeedforward.h b/wpimath/src/main/native/include/frc/controller/ElevatorFeedforward.h index 9be72a4ff6..93575276c5 100644 --- a/wpimath/src/main/native/include/frc/controller/ElevatorFeedforward.h +++ b/wpimath/src/main/native/include/frc/controller/ElevatorFeedforward.h @@ -216,6 +216,34 @@ class ElevatorFeedforward { return MaxAchievableAcceleration(-maxVoltage, velocity); } + /** + * Sets the static gain. + * + * @param kS The static gain. + */ + constexpr void SetKs(units::volt_t kS) { this->kS = kS; } + + /** + * Sets the gravity gain. + * + * @param kG The gravity gain. + */ + constexpr void SetKg(units::volt_t kG) { this->kG = kG; } + + /** + * Sets the velocity gain. + * + * @param kV The velocity gain. + */ + constexpr void SetKv(units::unit_t kV) { this->kV = kV; } + + /** + * Sets the acceleration gain. + * + * @param kA The acceleration gain. + */ + constexpr void SetKa(units::unit_t kA) { this->kA = kA; } + /** * Returns the static gain. * diff --git a/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h b/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h index 4aeea81d2c..e12a76384e 100644 --- a/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h +++ b/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h @@ -178,6 +178,27 @@ class SimpleMotorFeedforward { return MaxAchievableAcceleration(-maxVoltage, velocity); } + /** + * Sets the static gain. + * + * @param kS The static gain. + */ + constexpr void SetKs(units::volt_t kS) { this->kS = kS; } + + /** + * Sets the velocity gain. + * + * @param kV The velocity gain. + */ + constexpr void SetKv(units::unit_t kV) { this->kV = kV; } + + /** + * Sets the acceleration gain. + * + * @param kA The acceleration gain. + */ + constexpr void SetKa(units::unit_t kA) { this->kA = kA; } + /** * Returns the static gain. * diff --git a/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h b/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h index 9c3a3c88df..9b520dff6e 100644 --- a/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h +++ b/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h @@ -59,7 +59,11 @@ struct WPILIB_DLLEXPORT ChassisSpeeds { * y-axis, and omega * dt around the z-axis). * * This is useful for compensating for translational skew when translating and - * rotating a swerve drivetrain. + * rotating a holonomic (swerve or mecanum) drivetrain. However, scaling down + * the ChassisSpeeds after discretizing (e.g., when desaturating swerve module + * speeds) rotates the direction of net motion in the opposite direction of + * rotational velocity, introducing a different translational skew which is + * not accounted for by discretization. * * @param dt The duration of the timestep the speeds should be applied for. * @return Discretized ChassisSpeeds. diff --git a/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h b/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h index 8c56467893..2aa2a88523 100644 --- a/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h @@ -333,6 +333,11 @@ class SwerveDriveKinematics * the absolute threshold, while maintaining the ratio of speeds between * modules. * + * Scaling down the module speeds rotates the direction of net motion in the + * opposite direction of rotational velocity, which makes discretizing the + * chassis speeds inaccurate because the discretization did not account for + * this translational skew. + * * @param moduleStates Reference to array of module states. The array will be * mutated with the normalized speeds! * @param attainableMaxSpeed The absolute max speed that a module can reach. @@ -368,6 +373,11 @@ class SwerveDriveKinematics * the absolute threshold, while maintaining the ratio of speeds between * modules. * + * Scaling down the module speeds rotates the direction of net motion in the + * opposite direction of rotational velocity, which makes discretizing the + * chassis speeds inaccurate because the discretization did not account for + * this translational skew. + * * @param moduleStates Reference to array of module states. The array will be * mutated with the normalized speeds! * @param desiredChassisSpeed The desired speed of the robot diff --git a/wpimath/src/main/native/include/units/base.h b/wpimath/src/main/native/include/units/base.h index 5d37594448..fc5ae4b29d 100644 --- a/wpimath/src/main/native/include/units/base.h +++ b/wpimath/src/main/native/include/units/base.h @@ -1759,7 +1759,7 @@ namespace units namespace traits { -#ifdef FOR_DOXYGEN_PURPOSOES_ONLY +#ifdef FOR_DOXYGEN_PURPOSES_ONLY /** * @ingroup TypeTraits * @brief Trait for accessing the publicly defined types of `units::unit_t` diff --git a/wpinet/BUILD.bazel b/wpinet/BUILD.bazel index 8a56e0b345..2fe22c2c25 100644 --- a/wpinet/BUILD.bazel +++ b/wpinet/BUILD.bazel @@ -123,6 +123,10 @@ cc_library( ] + ["native-srcs"], hdrs = glob(["src/main/native/include/**/*"]), includes = ["src/main/native/include"], + linkopts = select({ + "@bazel_tools//src/conditions:linux": ["-ldl"], + "//conditions:default": [], + }), strip_include_prefix = "src/main/native/include", visibility = ["//visibility:public"], deps = [ diff --git a/wpinet/src/main/native/cpp/WebServer.cpp b/wpinet/src/main/native/cpp/WebServer.cpp index 9efd76a190..baa8b9b4b1 100644 --- a/wpinet/src/main/native/cpp/WebServer.cpp +++ b/wpinet/src/main/native/cpp/WebServer.cpp @@ -270,6 +270,7 @@ void MyHttpConnection::ProcessRequest() { } // generate directory listing wpi::SmallString<64> formatBuf; + fs::path indexpath = fs::path{fullpath} / "index.html"; if (qmap.Get("format", formatBuf).value_or("") == "json") { wpi::json dirs = wpi::json::array(); wpi::json files = wpi::json::array(); @@ -288,6 +289,9 @@ void MyHttpConnection::ProcessRequest() { 200, "OK", "text/json", wpi::json{{"dirs", std::move(dirs)}, {"files", std::move(files)}} .dump()); + } else if (fs::exists(indexpath)) { + SendFileResponse(200, "OK", GetMimeType("html"), indexpath, + "Content-Disposition: filename=\"index.html\"\r\n"); } else { wpi::StringMap dirs; wpi::StringMap files; diff --git a/wpiunits/src/generate/main/java/Measure-interface.java.jinja b/wpiunits/src/generate/main/java/Measure-interface.java.jinja index 80ffe0a7e0..608900f2b5 100644 --- a/wpiunits/src/generate/main/java/Measure-interface.java.jinja +++ b/wpiunits/src/generate/main/java/Measure-interface.java.jinja @@ -86,11 +86,6 @@ public interface {{ helpers['type_decl'](name) }} extends Measure<{{ helpers['mt default {{ helpers['type_usage'](name) }} divide(double divisor) { return ({{ helpers['type_usage'](name) }}) div(divisor); } - - @Override - default {{ config[name]['divide']['Time'] or "Velocity<{}>".format(helpers['mtou'](name)) }} per(TimeUnit period) { - return div(period.of(1)); - } {% for unit in math_units -%} {% if unit == "Dimensionless" %} @Override @@ -147,6 +142,15 @@ public interface {{ helpers['type_decl'](name) }} extends Measure<{{ helpers['mt default {{ config[name]['divide'][unit] }} divide({{ unit }} divisor) { return div(divisor); } + + @Override + default {{ config[name]['divide'][unit] }} per({{ helpers['mtou'](unit) }} divisorUnit) { +{%- if unit == "Mult" or unit == "Per" %} + return div(divisorUnit.ofNative(1)); +{%- else %} + return div(divisorUnit.one()); +{%- endif %} + } {% elif unit == "Time" %} @Override default Velocity<{{ helpers['mtou'](name) }}> div({{ unit }} divisor) { @@ -164,6 +168,15 @@ public interface {{ helpers['type_decl'](name) }} extends Measure<{{ helpers['mt default Velocity<{{ helpers['mtou'](name) }}> divide({{ unit }} divisor) { return div(divisor); } + + @Override + default Velocity<{{ helpers['mtou'](name) }}> per({{ helpers['mtou'](unit) }} divisorUnit) { +{%- if unit == "Mult" or unit == "Per" %} + return div(divisorUnit.ofNative(1)); +{%- else %} + return div(divisorUnit.one()); +{%- endif %} + } {% elif unit == name %} @Override default Dimensionless div({{ unit }} divisor) { @@ -181,6 +194,11 @@ public interface {{ helpers['type_decl'](name) }} extends Measure<{{ helpers['mt default Dimensionless divide({{ unit }} divisor) { return div(divisor); } + + @Override + default Dimensionless per({{ helpers['mtou'](unit) }} divisorUnit) { + return div(divisorUnit.one()); + } {% else %} @Override default Per<{{ helpers['mtou'](name) }}, {{ helpers['mtou'](unit) }}> div({{ unit }} divisor) { @@ -198,6 +216,15 @@ public interface {{ helpers['type_decl'](name) }} extends Measure<{{ helpers['mt default Per<{{ helpers['mtou'](name) }}, {{ helpers['mtou'](unit) }}> divide({{ unit }} divisor) { return div(divisor); } + + @Override + default Per<{{ helpers['mtou'](name) }}, {{ helpers['mtou'](unit) }}> per({{ helpers['mtou'](unit) }} divisorUnit) { +{%- if unit == "Mult" or unit == "Per" %} + return div(divisorUnit.ofNative(1)); +{%- else %} + return div(divisorUnit.one()); +{%- endif %} + } {% endif -%} {% endif -%} {% endfor -%} diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Acceleration.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Acceleration.java index ac4f686097..9a007dae74 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Acceleration.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Acceleration.java @@ -87,11 +87,6 @@ public interface Acceleration extends Measure) div(divisor); } - @Override - default Velocity> per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult, AccelerationUnit> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Acceleration extends Measure, AccelerationUnit> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngleUnit> times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Acceleration extends Measure, AngleUnit> per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularAccelerationUnit> times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Acceleration extends Measure, AngularAccelerationUnit> per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularMomentumUnit> times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Acceleration extends Measure, AngularMomentumUnit> per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularVelocityUnit> times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Acceleration extends Measure, AngularVelocityUnit> per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, CurrentUnit> times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Acceleration extends Measure, CurrentUnit> per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Acceleration div(Dimensionless divisor) { return (Acceleration) unit().of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Acceleration extends Measure, DistanceUnit> per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, EnergyUnit> times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Acceleration extends Measure, EnergyUnit> per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, ForceUnit> times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Acceleration extends Measure, ForceUnit> per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, FrequencyUnit> times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Acceleration extends Measure, FrequencyUnit> per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearAccelerationUnit> times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Acceleration extends Measure, LinearAccelerationUnit> per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearMomentumUnit> times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Acceleration extends Measure, LinearMomentumUnit> per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearVelocityUnit> times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Acceleration extends Measure, LinearVelocityUnit> per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MassUnit> times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Acceleration extends Measure, MassUnit> per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MomentOfInertiaUnit> times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Acceleration extends Measure, MomentOfInertiaUnit> per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MultUnit> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Acceleration extends Measure, MultUnit> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult, PerUnit> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Acceleration extends Measure, PerUnit> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult, PowerUnit> times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Acceleration extends Measure, PowerUnit> per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, ResistanceUnit> times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Acceleration extends Measure, ResistanceUnit> per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TemperatureUnit> times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Acceleration extends Measure, TemperatureUnit> per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TimeUnit> times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Acceleration extends Measure> per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TorqueUnit> times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Acceleration extends Measure, TorqueUnit> per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, VelocityUnit> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Acceleration extends Measure, VelocityUnit> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, VoltageUnit> times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Acceleration extends Measure, VoltageUnit> per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Angle.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Angle.java index 23b9957241..812b239a7b 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Angle.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Angle.java @@ -87,11 +87,6 @@ public interface Angle extends Measure { return (Angle) div(divisor); } - @Override - default AngularVelocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Dimensionless per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Angle div(Dimensionless divisor) { return (Angle) Radians.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularVelocity times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default AngularVelocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Angle extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularAcceleration.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularAcceleration.java index d5cac08a79..d90cbe2056 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularAcceleration.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularAcceleration.java @@ -87,11 +87,6 @@ public interface AngularAcceleration extends Measure { return (AngularAcceleration) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Dimensionless per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularAcceleration div(Dimensionless divisor) { return (AngularAcceleration) RadiansPerSecondPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default AngularVelocity per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularVelocity times(Time multiplier) { @@ -597,6 +692,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface AngularAcceleration extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularMomentum.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularMomentum.java index 8d7bc6387e..ab1b0f15fd 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularMomentum.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularMomentum.java @@ -87,11 +87,6 @@ public interface AngularMomentum extends Measure { return (AngularMomentum) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Dimensionless per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default MomentOfInertia per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularMomentum div(Dimensionless divisor) { return (AngularMomentum) KilogramMetersSquaredPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface AngularMomentum extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularVelocity.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularVelocity.java index 9347eafa8b..37b4a28d57 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularVelocity.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularVelocity.java @@ -87,11 +87,6 @@ public interface AngularVelocity extends Measure { return (AngularVelocity) div(divisor); } - @Override - default AngularAcceleration per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Dimensionless per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularVelocity div(Dimensionless divisor) { return (AngularVelocity) RadiansPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularAcceleration times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Angle times(Time multiplier) { @@ -597,6 +692,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default AngularAcceleration per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface AngularVelocity extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -665,5 +775,10 @@ public interface AngularVelocity extends Measure { default Per divide(Voltage divisor) { return div(divisor); } + + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } default Frequency asFrequency() { return Hertz.of(baseUnitMagnitude()); } } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Current.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Current.java index 84ae1e04db..734272a138 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Current.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Current.java @@ -87,11 +87,6 @@ public interface Current extends Measure { return (Current) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Dimensionless per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Current div(Dimensionless divisor) { return (Current) Amps.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Voltage times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Power times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Current extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Dimensionless.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Dimensionless.java index 27e01a77a1..4447c270ee 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Dimensionless.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Dimensionless.java @@ -87,11 +87,6 @@ public interface Dimensionless extends Measure { return (Dimensionless) div(divisor); } - @Override - default Frequency per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Angle times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularAcceleration times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularMomentum times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularVelocity times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Current times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Dimensionless div(Dimensionless divisor) { return (Dimensionless) Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Energy times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Force times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Frequency times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearAcceleration times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearMomentum times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearVelocity times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mass times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default MomentOfInertia times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Power times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Resistance times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Temperature times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Time times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Frequency per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Torque times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Voltage times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Dimensionless extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Distance.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Distance.java index 7bfc52f736..e0f53a620e 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Distance.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Distance.java @@ -87,11 +87,6 @@ public interface Distance extends Measure { return (Distance) div(divisor); } - @Override - default LinearVelocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Distance div(Dimensionless divisor) { return (Distance) Meters.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Dimensionless per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Torque times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearVelocity times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Time per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default LinearVelocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Distance extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Energy.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Energy.java index ed125befe3..a98f55d5a8 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Energy.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Energy.java @@ -87,11 +87,6 @@ public interface Energy extends Measure { return (Energy) div(divisor); } - @Override - default Power per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Energy div(Dimensionless divisor) { return (Energy) Joules.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Dimensionless per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Power times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Power per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Energy extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Force.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Force.java index fa69b143f1..0233742892 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Force.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Force.java @@ -87,11 +87,6 @@ public interface Force extends Measure { return (Force) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Force div(Dimensionless divisor) { return (Force) Newtons.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Dimensionless per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Mass per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default LinearAcceleration per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Force extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Frequency.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Frequency.java index 1b69009db5..d18973a84d 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Frequency.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Frequency.java @@ -87,11 +87,6 @@ public interface Frequency extends Measure { return (Frequency) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularVelocity times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularAcceleration times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Frequency div(Dimensionless divisor) { return (Frequency) Hertz.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Dimensionless per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearAcceleration times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Dimensionless times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Frequency extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -665,6 +775,11 @@ public interface Frequency extends Measure { default Per divide(Voltage divisor) { return div(divisor); } + + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } /** Converts this frequency to the time period between cycles. */ default Time asPeriod() { return Seconds.of(1 / baseUnitMagnitude()); } } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearAcceleration.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearAcceleration.java index dc8f6d26b8..875ef937b1 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearAcceleration.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearAcceleration.java @@ -87,11 +87,6 @@ public interface LinearAcceleration extends Measure { return (LinearAcceleration) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearAcceleration div(Dimensionless divisor) { return (LinearAcceleration) MetersPerSecondPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default LinearVelocity per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Dimensionless per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearVelocity times(Time multiplier) { @@ -597,6 +692,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface LinearAcceleration extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearMomentum.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearMomentum.java index 2a7ce3341d..c1bf6d7f11 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearMomentum.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearMomentum.java @@ -87,11 +87,6 @@ public interface LinearMomentum extends Measure { return (LinearMomentum) div(divisor); } - @Override - default Force per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearMomentum div(Dimensionless divisor) { return (LinearMomentum) KilogramMetersPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Force times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Dimensionless per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Mass per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default LinearVelocity per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Force per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface LinearMomentum extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearVelocity.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearVelocity.java index e45aa5474a..7ed8cc1e5f 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearVelocity.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearVelocity.java @@ -87,11 +87,6 @@ public interface LinearVelocity extends Measure { return (LinearVelocity) div(divisor); } - @Override - default LinearAcceleration per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearVelocity div(Dimensionless divisor) { return (LinearVelocity) MetersPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearAcceleration times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Dimensionless per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Distance times(Time multiplier) { @@ -597,6 +692,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default LinearAcceleration per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface LinearVelocity extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mass.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mass.java index 81a0f1507f..507977df5c 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mass.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mass.java @@ -87,11 +87,6 @@ public interface Mass extends Measure { return (Mass) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mass div(Dimensionless divisor) { return (Mass) Kilograms.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Force times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Dimensionless per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Mass extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MomentOfInertia.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MomentOfInertia.java index b831bcffc6..21f04fbeb7 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MomentOfInertia.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MomentOfInertia.java @@ -87,11 +87,6 @@ public interface MomentOfInertia extends Measure { return (MomentOfInertia) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularMomentum times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default MomentOfInertia div(Dimensionless divisor) { return (MomentOfInertia) KilogramSquareMeters.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Dimensionless per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface MomentOfInertia extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mult.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mult.java index 3b7dcf840c..5cee72363d 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mult.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mult.java @@ -87,11 +87,6 @@ public interface Mult extends Measure) div(divisor); } - @Override - default Velocity> per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult, AccelerationUnit> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Mult extends Measure, AccelerationUnit> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngleUnit> times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Mult extends Measure, AngleUnit> per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularAccelerationUnit> times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Mult extends Measure, AngularAccelerationUnit> per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularMomentumUnit> times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Mult extends Measure, AngularMomentumUnit> per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularVelocityUnit> times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Mult extends Measure, AngularVelocityUnit> per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, CurrentUnit> times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Mult extends Measure, CurrentUnit> per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult div(Dimensionless divisor) { return (Mult) unit().of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Mult extends Measure, DistanceUnit> per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, EnergyUnit> times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Mult extends Measure, EnergyUnit> per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, ForceUnit> times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Mult extends Measure, ForceUnit> per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, FrequencyUnit> times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Mult extends Measure, FrequencyUnit> per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearAccelerationUnit> times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Mult extends Measure, LinearAccelerationUnit> per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearMomentumUnit> times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Mult extends Measure, LinearMomentumUnit> per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearVelocityUnit> times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Mult extends Measure, LinearVelocityUnit> per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MassUnit> times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Mult extends Measure, MassUnit> per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MomentOfInertiaUnit> times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Mult extends Measure, MomentOfInertiaUnit> per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MultUnit> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Mult extends Measure, MultUnit> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult, PerUnit> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Mult extends Measure, PerUnit> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult, PowerUnit> times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Mult extends Measure, PowerUnit> per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, ResistanceUnit> times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Mult extends Measure, ResistanceUnit> per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TemperatureUnit> times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Mult extends Measure, TemperatureUnit> per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TimeUnit> times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Mult extends Measure> per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TorqueUnit> times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Mult extends Measure, TorqueUnit> per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, VelocityUnit> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Mult extends Measure, VelocityUnit> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, VoltageUnit> times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Mult extends Measure, VoltageUnit> per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Per.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Per.java index e46fb50f89..2c1af67794 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Per.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Per.java @@ -87,11 +87,6 @@ public interface Per extends Measur return (Per) div(divisor); } - @Override - default Velocity> per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult, AccelerationUnit> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, AccelerationUnit> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngleUnit> times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, AngleUnit> per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularAccelerationUnit> times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, AngularAccelerationUnit> per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularMomentumUnit> times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, AngularMomentumUnit> per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularVelocityUnit> times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, AngularVelocityUnit> per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, CurrentUnit> times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, CurrentUnit> per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Per div(Dimensionless divisor) { return (Per) unit().of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, DistanceUnit> per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, EnergyUnit> times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, EnergyUnit> per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, ForceUnit> times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, ForceUnit> per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, FrequencyUnit> times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, FrequencyUnit> per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearAccelerationUnit> times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, LinearAccelerationUnit> per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearMomentumUnit> times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, LinearMomentumUnit> per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearVelocityUnit> times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, LinearVelocityUnit> per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MassUnit> times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, MassUnit> per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MomentOfInertiaUnit> times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, MomentOfInertiaUnit> per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MultUnit> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, MultUnit> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult, PerUnit> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, PerUnit> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult, PowerUnit> times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, PowerUnit> per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, ResistanceUnit> times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, ResistanceUnit> per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TemperatureUnit> times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, TemperatureUnit> per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TimeUnit> times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Velocity> per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TorqueUnit> times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, TorqueUnit> per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, VelocityUnit> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Per extends Measur return div(divisor); } + @Override + default Per, VelocityUnit> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, VoltageUnit> times(Voltage multiplier) { @@ -665,6 +775,11 @@ public interface Per extends Measur default Per, VoltageUnit> divide(Voltage divisor) { return div(divisor); } + + @Override + default Per, VoltageUnit> per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } default Measure timesDivisor(Measure multiplier) { return (Measure) baseUnit().numerator().ofBaseUnits(baseUnitMagnitude() * multiplier.baseUnitMagnitude()); } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Power.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Power.java index a666094881..d94ddcde38 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Power.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Power.java @@ -87,11 +87,6 @@ public interface Power extends Measure { return (Power) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Voltage per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Power div(Dimensionless divisor) { return (Power) Watts.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Frequency per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Dimensionless per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Energy times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Power extends Measure { return div(divisor); } + @Override + default Current per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Resistance.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Resistance.java index 28932b2c70..52d15b091a 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Resistance.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Resistance.java @@ -87,11 +87,6 @@ public interface Resistance extends Measure { return (Resistance) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Voltage times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Resistance div(Dimensionless divisor) { return (Resistance) Ohms.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Dimensionless per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Resistance extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Temperature.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Temperature.java index b10efd810d..2d7983b846 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Temperature.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Temperature.java @@ -87,11 +87,6 @@ public interface Temperature extends Measure { return (Temperature) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Temperature div(Dimensionless divisor) { return (Temperature) Kelvin.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Dimensionless per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Temperature extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Time.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Time.java index dccfda609d..4244325a26 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Time.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Time.java @@ -87,11 +87,6 @@ public interface Time extends Measure { return (Time) div(divisor); } - @Override - default Dimensionless per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default AngularVelocity times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Angle times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Time div(Dimensionless divisor) { return (Time) Seconds.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Dimensionless times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default LinearVelocity times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Distance times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Dimensionless per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Time extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -665,5 +775,10 @@ public interface Time extends Measure { default Per divide(Voltage divisor) { return div(divisor); } + + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } default Frequency asFrequency() { return Hertz.of(1 / baseUnitMagnitude()); } } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Torque.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Torque.java index e53dbaad94..cc7ac69da5 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Torque.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Torque.java @@ -87,11 +87,6 @@ public interface Torque extends Measure { return (Torque) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Torque div(Dimensionless divisor) { return (Torque) NewtonMeters.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Force per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Distance per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Dimensionless per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Torque extends Measure { return div(divisor); } + @Override + default Per per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Velocity.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Velocity.java index 056924849e..ac6df04e1f 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Velocity.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Velocity.java @@ -87,11 +87,6 @@ public interface Velocity extends Measure> { return (Velocity) div(divisor); } - @Override - default Velocity> per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult, AccelerationUnit> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, AccelerationUnit> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngleUnit> times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, AngleUnit> per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularAccelerationUnit> times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, AngularAccelerationUnit> per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularMomentumUnit> times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, AngularMomentumUnit> per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, AngularVelocityUnit> times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, AngularVelocityUnit> per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, CurrentUnit> times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, CurrentUnit> per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Velocity div(Dimensionless divisor) { return (Velocity) unit().of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, DistanceUnit> per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, EnergyUnit> times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, EnergyUnit> per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, ForceUnit> times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, ForceUnit> per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, FrequencyUnit> times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, FrequencyUnit> per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearAccelerationUnit> times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, LinearAccelerationUnit> per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearMomentumUnit> times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, LinearMomentumUnit> per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, LinearVelocityUnit> times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, LinearVelocityUnit> per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MassUnit> times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, MassUnit> per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MomentOfInertiaUnit> times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, MomentOfInertiaUnit> per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, MultUnit> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, MultUnit> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult, PerUnit> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, PerUnit> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult, PowerUnit> times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, PowerUnit> per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, ResistanceUnit> times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, ResistanceUnit> per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TemperatureUnit> times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, TemperatureUnit> per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Measure times(Time multiplier) { return (Measure) unit().numerator().ofBaseUnits(baseUnitMagnitude() * multiplier.baseUnitMagnitude()); @@ -596,6 +691,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Velocity> per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, TorqueUnit> times(Torque multiplier) { @@ -619,6 +719,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, TorqueUnit> per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, VelocityUnit> times(Velocity multiplier) { @@ -642,6 +747,11 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, VelocityUnit> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult, VoltageUnit> times(Voltage multiplier) { @@ -665,4 +775,9 @@ public interface Velocity extends Measure> { return div(divisor); } + @Override + default Per, VoltageUnit> per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Voltage.java b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Voltage.java index 98ceecedaa..33404865fd 100644 --- a/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Voltage.java +++ b/wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Voltage.java @@ -87,11 +87,6 @@ public interface Voltage extends Measure { return (Voltage) div(divisor); } - @Override - default Velocity per(TimeUnit period) { - return div(period.of(1)); - } - @Override default Mult> times(Acceleration multiplier) { @@ -115,6 +110,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per> per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Angle multiplier) { @@ -138,6 +138,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularAcceleration multiplier) { @@ -161,6 +166,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularMomentum multiplier) { @@ -184,6 +194,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(AngularVelocity multiplier) { @@ -207,6 +222,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Power times(Current multiplier) { @@ -230,6 +250,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Resistance per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Voltage div(Dimensionless divisor) { return (Voltage) Volts.of(baseUnitMagnitude() / divisor.baseUnitMagnitude()); @@ -275,6 +300,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Energy multiplier) { @@ -298,6 +328,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Force multiplier) { @@ -321,6 +356,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Frequency multiplier) { @@ -344,6 +384,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearAcceleration multiplier) { @@ -367,6 +412,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearMomentum multiplier) { @@ -390,6 +440,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(LinearVelocity multiplier) { @@ -413,6 +468,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Mass multiplier) { @@ -436,6 +496,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(MomentOfInertia multiplier) { @@ -459,6 +524,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Mult multiplier) { @@ -482,6 +552,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per> per(MultUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult> times(Per multiplier) { @@ -505,6 +580,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per> per(PerUnit divisorUnit) { + return div(divisorUnit.ofNative(1)); + } + @Override default Mult times(Power multiplier) { @@ -528,6 +608,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Resistance multiplier) { @@ -551,6 +636,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Current per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Temperature multiplier) { @@ -574,6 +664,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Time multiplier) { @@ -597,6 +692,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Velocity per(TimeUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Torque multiplier) { @@ -620,6 +720,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult> times(Velocity multiplier) { @@ -643,6 +748,11 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Per> per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + @Override default Mult times(Voltage multiplier) { @@ -666,4 +776,9 @@ public interface Voltage extends Measure { return div(divisor); } + @Override + default Dimensionless per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + } diff --git a/wpiunits/src/main/java/edu/wpi/first/units/Measure.java b/wpiunits/src/main/java/edu/wpi/first/units/Measure.java index 28d6d9614a..6a436194b7 100644 --- a/wpiunits/src/main/java/edu/wpi/first/units/Measure.java +++ b/wpiunits/src/main/java/edu/wpi/first/units/Measure.java @@ -1021,6 +1021,270 @@ public interface Measure extends Comparable> { .ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude()); } + /** + * Divides this measure by an acceleration unit and returns the result in the most appropriate + * unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(AccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by an angle unit and returns the result in the most appropriate unit. This + * is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(AngleUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by an angular acceleration unit and returns the result in the most + * appropriate unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(AngularAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by an angular momentum unit and returns the result in the most appropriate + * unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(AngularMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by an angular velocity unit and returns the result in the most appropriate + * unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(AngularVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a unit of electric current and returns the result in the most + * appropriate unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(CurrentUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a distance unit and returns the result in the most appropriate unit. + * This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(DistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by an energy unit and returns the result in the most appropriate unit. + * This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(EnergyUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a force unit and returns the result in the most appropriate unit. This + * is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(ForceUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a frequency unit and returns the result in the most appropriate unit. + * This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(FrequencyUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a linear acceleration unit and returns the result in the most + * appropriate unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(LinearAccelerationUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a linear momentum unit and returns the result in the most appropriate + * unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(LinearMomentumUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a linear velocity unit and returns the result in the most appropriate + * unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(LinearVelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a mass unit and returns the result in the most appropriate unit. This + * is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(MassUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a moment of inertia unit and returns the result in the most appropriate + * unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(MomentOfInertiaUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a generic compound unit and returns the result in the most appropriate + * unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(MultUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a power unit and returns the result in the most appropriate unit. This + * is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(PowerUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a generic ratio unit and returns the result in the most appropriate + * unit. This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(PerUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a temperature unit and returns the result in the most appropriate unit. + * This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(TemperatureUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a time period and returns the result in the most appropriate unit. This + * is equivalent to {@code div(period.of(1))}. + * + * @param period the time period measurement to divide by. + * @return the division result + */ + default Measure per(TimeUnit period) { + return div(period.of(1)); + } + + /** + * Divides this measure by a torque unit and returns the result in the most appropriate unit. This + * is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(TorqueUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a velocity unit and returns the result in the most appropriate unit. + * This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(VelocityUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a voltage unit and returns the result in the most appropriate unit. + * This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(VoltageUnit divisorUnit) { + return div(divisorUnit.one()); + } + + /** + * Divides this measure by a resistance unit and returns the result in the most appropriate unit. + * This is equivalent to {@code div(divisorUnit.of(1))}. + * + * @param divisorUnit the unit to divide by. + * @return the division result + */ + default Measure per(ResistanceUnit divisorUnit) { + return div(divisorUnit.one()); + } + /** * Divides this measure by a unitless scalar and returns the result. * @@ -1371,17 +1635,6 @@ public interface Measure extends Comparable> { baseUnitMagnitude() / divisor.baseUnitMagnitude(), divisor.unit().denominator()); } - /** - * Divides this measure by a time period and returns the result in the most appropriate unit. This - * is equivalent to {@code div(period.of(1))}. - * - * @param period the time period measurement to divide by. - * @return the division result - */ - default Measure per(TimeUnit period) { - return div(period.of(1)); - } - /** * Checks if this measure is near another measure of the same unit. Provide a variance threshold * for use for a +/- scalar, such as 0.05 for +/- 5%. diff --git a/wpiunits/src/main/java/edu/wpi/first/units/VelocityUnit.java b/wpiunits/src/main/java/edu/wpi/first/units/VelocityUnit.java index d954166db4..45374cd39c 100644 --- a/wpiunits/src/main/java/edu/wpi/first/units/VelocityUnit.java +++ b/wpiunits/src/main/java/edu/wpi/first/units/VelocityUnit.java @@ -90,14 +90,14 @@ public final class VelocityUnit extends PerUnit { @Override @SuppressWarnings("unchecked") - public Measure> zero() { - return (Measure>) super.zero(); + public Velocity zero() { + return (Velocity) super.zero(); } @Override @SuppressWarnings("unchecked") - public Measure> one() { - return (Measure>) super.one(); + public Velocity one() { + return (Velocity) super.one(); } @Override diff --git a/wpiutil/src/main/native/cpp/RuntimeCheck.cpp b/wpiutil/src/main/native/cpp/RuntimeCheck.cpp index 6cead1a8ab..79ed623580 100644 --- a/wpiutil/src/main/native/cpp/RuntimeCheck.cpp +++ b/wpiutil/src/main/native/cpp/RuntimeCheck.cpp @@ -7,7 +7,7 @@ #ifdef _WIN32 #include #include - +#pragma comment(lib, "version.lib") // for VerQueryValueW #include "Windows.h" extern "C" int32_t WPI_IsRuntimeValid(uint32_t* foundMajor, uint32_t* foundMinor, diff --git a/wpiutil/src/main/native/windows/StackTrace.cpp b/wpiutil/src/main/native/windows/StackTrace.cpp index db17bf8e83..ed7cf61afb 100644 --- a/wpiutil/src/main/native/windows/StackTrace.cpp +++ b/wpiutil/src/main/native/windows/StackTrace.cpp @@ -6,35 +6,13 @@ #include -#include "StackWalker.h" -#include "wpi/ConvertUTF.h" -#include "wpi/SmallString.h" - #if defined(_MSC_VER) -namespace { -class StackTraceWalker : public StackWalker { - public: - explicit StackTraceWalker(std::string& output) : m_output(output) {} - - void OnOutput(LPCTSTR szText) override; - - private: - std::string& m_output; -}; -} // namespace - -void StackTraceWalker::OnOutput(LPCTSTR szText) { - m_output.append(szText); -} - namespace wpi { std::string GetStackTraceDefault(int offset) { - // TODO: implement offset - std::string output; - StackTraceWalker walker(output); - return output; + // FIXME: Use C++23 std::stacktrace + return ""; } } // namespace wpi diff --git a/wpiutil/src/main/native/windows/StackWalker.cpp b/wpiutil/src/main/native/windows/StackWalker.cpp deleted file mode 100644 index b2bcbaa447..0000000000 --- a/wpiutil/src/main/native/windows/StackWalker.cpp +++ /dev/null @@ -1,1549 +0,0 @@ -/********************************************************************** - * - * StackWalker.cpp - * https://github.com/JochenKalmbach/StackWalker - * - * Old location: http://stackwalker.codeplex.com/ - * - * - * History: - * 2005-07-27 v1 - First public release on http://www.codeproject.com/ - * http://www.codeproject.com/threads/StackWalker.asp - * 2005-07-28 v2 - Changed the params of the constructor and ShowCallstack - * (to simplify the usage) - * 2005-08-01 v3 - Changed to use 'CONTEXT_FULL' instead of CONTEXT_ALL - * (should also be enough) - * - Changed to compile correctly with the PSDK of VC7.0 - * (GetFileVersionInfoSizeA and GetFileVersionInfoA is wrongly defined: - * it uses LPSTR instead of LPCSTR as first parameter) - * - Added declarations to support VC5/6 without using 'dbghelp.h' - * - Added a 'pUserData' member to the ShowCallstack function and the - * PReadProcessMemoryRoutine declaration (to pass some user-defined data, - * which can be used in the readMemoryFunction-callback) - * 2005-08-02 v4 - OnSymInit now also outputs the OS-Version by default - * - Added example for doing an exception-callstack-walking in main.cpp - * (thanks to owillebo: http://www.codeproject.com/script/profile/whos_who.asp?id=536268) - * 2005-08-05 v5 - Removed most Lint (http://www.gimpel.com/) errors... thanks to Okko Willeboordse! - * 2008-08-04 v6 - Fixed Bug: Missing LEAK-end-tag - * http://www.codeproject.com/KB/applications/leakfinder.aspx?msg=2502890#xx2502890xx - * Fixed Bug: Compiled with "WIN32_LEAN_AND_MEAN" - * http://www.codeproject.com/KB/applications/leakfinder.aspx?msg=1824718#xx1824718xx - * Fixed Bug: Compiling with "/Wall" - * http://www.codeproject.com/KB/threads/StackWalker.aspx?msg=2638243#xx2638243xx - * Fixed Bug: Now checking SymUseSymSrv - * http://www.codeproject.com/KB/threads/StackWalker.aspx?msg=1388979#xx1388979xx - * Fixed Bug: Support for recursive function calls - * http://www.codeproject.com/KB/threads/StackWalker.aspx?msg=1434538#xx1434538xx - * Fixed Bug: Missing FreeLibrary call in "GetModuleListTH32" - * http://www.codeproject.com/KB/threads/StackWalker.aspx?msg=1326923#xx1326923xx - * Fixed Bug: SymDia is number 7, not 9! - * 2008-09-11 v7 For some (undocumented) reason, dbhelp.h is needing a packing of 8! - * Thanks to Teajay which reported the bug... - * http://www.codeproject.com/KB/applications/leakfinder.aspx?msg=2718933#xx2718933xx - * 2008-11-27 v8 Debugging Tools for Windows are now stored in a different directory - * Thanks to Luiz Salamon which reported this "bug"... - * http://www.codeproject.com/KB/threads/StackWalker.aspx?msg=2822736#xx2822736xx - * 2009-04-10 v9 License slightly corrected ( replaced) - * 2009-11-01 v10 Moved to http://stackwalker.codeplex.com/ - * 2009-11-02 v11 Now try to use IMAGEHLP_MODULE64_V3 if available - * 2010-04-15 v12 Added support for VS2010 RTM - * 2010-05-25 v13 Now using secure MyStrcCpy. Thanks to luke.simon: - * http://www.codeproject.com/KB/applications/leakfinder.aspx?msg=3477467#xx3477467xx - * 2013-01-07 v14 Runtime Check Error VS2010 Debug Builds fixed: - * http://stackwalker.codeplex.com/workitem/10511 - * - * - * LICENSE (http://www.opensource.org/licenses/bsd-license.php) - * - * Copyright (c) 2005-2013, Jochen Kalmbach - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * - * Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * Neither the name of Jochen Kalmbach nor the names of its contributors may be - * used to endorse or promote products derived from this software without - * specific prior written permission. - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, - * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND - * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -#include "StackWalker.h" - -#include -#include -#include -#include -#include - -#pragma comment(lib, "version.lib") // for "VerQueryValue" -#pragma comment(lib, "Advapi32.lib") // for "GetUserName" - -#pragma warning(disable : 4826) -#if _MSC_VER >= 1900 -#pragma warning(disable : 4091) // For fix unnamed enums from DbgHelp.h -#endif - - -// If VC7 and later, then use the shipped 'dbghelp.h'-file -#pragma pack(push, 8) -#if _MSC_VER >= 1300 -#include -#else -// inline the important dbghelp.h-declarations... -typedef enum -{ - SymNone = 0, - SymCoff, - SymCv, - SymPdb, - SymExport, - SymDeferred, - SymSym, - SymDia, - SymVirtual, - NumSymTypes -} SYM_TYPE; -typedef struct _IMAGEHLP_LINE64 -{ - DWORD SizeOfStruct; // set to sizeof(IMAGEHLP_LINE64) - PVOID Key; // internal - DWORD LineNumber; // line number in file - PCHAR FileName; // full filename - DWORD64 Address; // first instruction of line -} IMAGEHLP_LINE64, *PIMAGEHLP_LINE64; -typedef struct _IMAGEHLP_MODULE64 -{ - DWORD SizeOfStruct; // set to sizeof(IMAGEHLP_MODULE64) - DWORD64 BaseOfImage; // base load address of module - DWORD ImageSize; // virtual size of the loaded module - DWORD TimeDateStamp; // date/time stamp from pe header - DWORD CheckSum; // checksum from the pe header - DWORD NumSyms; // number of symbols in the symbol table - SYM_TYPE SymType; // type of symbols loaded - CHAR ModuleName[32]; // module name - CHAR ImageName[256]; // image name - CHAR LoadedImageName[256]; // symbol file name -} IMAGEHLP_MODULE64, *PIMAGEHLP_MODULE64; -typedef struct _IMAGEHLP_SYMBOL64 -{ - DWORD SizeOfStruct; // set to sizeof(IMAGEHLP_SYMBOL64) - DWORD64 Address; // virtual address including dll base address - DWORD Size; // estimated size of symbol, can be zero - DWORD Flags; // info about the symbols, see the SYMF defines - DWORD MaxNameLength; // maximum size of symbol name in 'Name' - CHAR Name[1]; // symbol name (null terminated string) -} IMAGEHLP_SYMBOL64, *PIMAGEHLP_SYMBOL64; -typedef enum -{ - AddrMode1616, - AddrMode1632, - AddrModeReal, - AddrModeFlat -} ADDRESS_MODE; -typedef struct _tagADDRESS64 -{ - DWORD64 Offset; - WORD Segment; - ADDRESS_MODE Mode; -} ADDRESS64, *LPADDRESS64; -typedef struct _KDHELP64 -{ - DWORD64 Thread; - DWORD ThCallbackStack; - DWORD ThCallbackBStore; - DWORD NextCallback; - DWORD FramePointer; - DWORD64 KiCallUserMode; - DWORD64 KeUserCallbackDispatcher; - DWORD64 SystemRangeStart; - DWORD64 Reserved[8]; -} KDHELP64, *PKDHELP64; -typedef struct _tagSTACKFRAME64 -{ - ADDRESS64 AddrPC; // program counter - ADDRESS64 AddrReturn; // return address - ADDRESS64 AddrFrame; // frame pointer - ADDRESS64 AddrStack; // stack pointer - ADDRESS64 AddrBStore; // backing store pointer - PVOID FuncTableEntry; // pointer to pdata/fpo or NULL - DWORD64 Params[4]; // possible arguments to the function - BOOL Far; // WOW far call - BOOL Virtual; // is this a virtual frame? - DWORD64 Reserved[3]; - KDHELP64 KdHelp; -} STACKFRAME64, *LPSTACKFRAME64; -typedef BOOL(__stdcall* PREAD_PROCESS_MEMORY_ROUTINE64)(HANDLE hProcess, - DWORD64 qwBaseAddress, - PVOID lpBuffer, - DWORD nSize, - LPDWORD lpNumberOfBytesRead); -typedef PVOID(__stdcall* PFUNCTION_TABLE_ACCESS_ROUTINE64)(HANDLE hProcess, DWORD64 AddrBase); -typedef DWORD64(__stdcall* PGET_MODULE_BASE_ROUTINE64)(HANDLE hProcess, DWORD64 Address); -typedef DWORD64(__stdcall* PTRANSLATE_ADDRESS_ROUTINE64)(HANDLE hProcess, - HANDLE hThread, - LPADDRESS64 lpaddr); - -// clang-format off -#define SYMOPT_CASE_INSENSITIVE 0x00000001 -#define SYMOPT_UNDNAME 0x00000002 -#define SYMOPT_DEFERRED_LOADS 0x00000004 -#define SYMOPT_NO_CPP 0x00000008 -#define SYMOPT_LOAD_LINES 0x00000010 -#define SYMOPT_OMAP_FIND_NEAREST 0x00000020 -#define SYMOPT_LOAD_ANYTHING 0x00000040 -#define SYMOPT_IGNORE_CVREC 0x00000080 -#define SYMOPT_NO_UNQUALIFIED_LOADS 0x00000100 -#define SYMOPT_FAIL_CRITICAL_ERRORS 0x00000200 -#define SYMOPT_EXACT_SYMBOLS 0x00000400 -#define SYMOPT_ALLOW_ABSOLUTE_SYMBOLS 0x00000800 -#define SYMOPT_IGNORE_NT_SYMPATH 0x00001000 -#define SYMOPT_INCLUDE_32BIT_MODULES 0x00002000 -#define SYMOPT_PUBLICS_ONLY 0x00004000 -#define SYMOPT_NO_PUBLICS 0x00008000 -#define SYMOPT_AUTO_PUBLICS 0x00010000 -#define SYMOPT_NO_IMAGE_SEARCH 0x00020000 -#define SYMOPT_SECURE 0x00040000 -#define SYMOPT_DEBUG 0x80000000 -#define UNDNAME_COMPLETE (0x0000) // Enable full undecoration -#define UNDNAME_NAME_ONLY (0x1000) // Crack only the name for primary declaration; -// clang-format on - -#endif // _MSC_VER < 1300 -#pragma pack(pop) - -// Some missing defines (for VC5/6): -#ifndef INVALID_FILE_ATTRIBUTES -#define INVALID_FILE_ATTRIBUTES ((DWORD)-1) -#endif - -// secure-CRT_functions are only available starting with VC8 -#if _MSC_VER < 1400 -#define strcpy_s(dst, len, src) strcpy(dst, src) -#define strncpy_s(dst, len, src, maxLen) strncpy(dst, len, src) -#define strcat_s(dst, len, src) strcat(dst, src) -#define _snprintf_s _snprintf -#define _tcscat_s _tcscat -#endif - -static void MyStrCpy(char* szDest, size_t nMaxDestSize, const char* szSrc) -{ - if (nMaxDestSize <= 0) - return; - strncpy_s(szDest, nMaxDestSize, szSrc, _TRUNCATE); - // INFO: _TRUNCATE will ensure that it is null-terminated; - // but with older compilers (<1400) it uses "strncpy" and this does not!) - szDest[nMaxDestSize - 1] = 0; -} // MyStrCpy - -// Normally it should be enough to use 'CONTEXT_FULL' (better would be 'CONTEXT_ALL') -#define USED_CONTEXT_FLAGS CONTEXT_FULL - -class StackWalkerInternal -{ -public: - StackWalkerInternal(StackWalker* parent, HANDLE hProcess, PCONTEXT ctx) - { - m_parent = parent; - m_hDbhHelp = NULL; - pSC = NULL; - m_hProcess = hProcess; - pSFTA = NULL; - pSGLFA = NULL; - pSGMB = NULL; - pSGMI = NULL; - pSGO = NULL; - pSGSFA = NULL; - pSI = NULL; - pSLM = NULL; - pSSO = NULL; - pSW = NULL; - pUDSN = NULL; - pSGSP = NULL; - m_ctx.ContextFlags = 0; - if (ctx != NULL) - m_ctx = *ctx; - } - - ~StackWalkerInternal() - { - if (pSC != NULL) - pSC(m_hProcess); // SymCleanup - if (m_hDbhHelp != NULL) - FreeLibrary(m_hDbhHelp); - m_hDbhHelp = NULL; - m_parent = NULL; - } - - BOOL Init(LPCSTR szSymPath) - { - if (m_parent == NULL) - return FALSE; - // Dynamically load the Entry-Points for dbghelp.dll: - // First try to load the newest one from - TCHAR szTemp[4096]; - // But before we do this, we first check if the ".local" file exists - if (GetModuleFileName(NULL, szTemp, 4096) > 0) - { - _tcscat_s(szTemp, _T(".local")); - if (GetFileAttributes(szTemp) == INVALID_FILE_ATTRIBUTES) - { - // ".local" file does not exist, so we can try to load the dbghelp.dll from the "Debugging Tools for Windows" - // Ok, first try the new path according to the architecture: -#ifdef _M_IX86 - if ((m_hDbhHelp == NULL) && (GetEnvironmentVariable(_T("ProgramFiles"), szTemp, 4096) > 0)) - { - _tcscat_s(szTemp, _T("\\Debugging Tools for Windows (x86)\\dbghelp.dll")); - // now check if the file exists: - if (GetFileAttributes(szTemp) != INVALID_FILE_ATTRIBUTES) - { - m_hDbhHelp = LoadLibrary(szTemp); - } - } -#elif _M_X64 - if ((m_hDbhHelp == NULL) && (GetEnvironmentVariable(_T("ProgramFiles"), szTemp, 4096) > 0)) - { - _tcscat_s(szTemp, _T("\\Debugging Tools for Windows (x64)\\dbghelp.dll")); - // now check if the file exists: - if (GetFileAttributes(szTemp) != INVALID_FILE_ATTRIBUTES) - { - m_hDbhHelp = LoadLibrary(szTemp); - } - } -#elif _M_IA64 - if ((m_hDbhHelp == NULL) && (GetEnvironmentVariable(_T("ProgramFiles"), szTemp, 4096) > 0)) - { - _tcscat_s(szTemp, _T("\\Debugging Tools for Windows (ia64)\\dbghelp.dll")); - // now check if the file exists: - if (GetFileAttributes(szTemp) != INVALID_FILE_ATTRIBUTES) - { - m_hDbhHelp = LoadLibrary(szTemp); - } - } -#endif - // If still not found, try the old directories... - if ((m_hDbhHelp == NULL) && (GetEnvironmentVariable(_T("ProgramFiles"), szTemp, 4096) > 0)) - { - _tcscat_s(szTemp, _T("\\Debugging Tools for Windows\\dbghelp.dll")); - // now check if the file exists: - if (GetFileAttributes(szTemp) != INVALID_FILE_ATTRIBUTES) - { - m_hDbhHelp = LoadLibrary(szTemp); - } - } -#if defined _M_X64 || defined _M_IA64 - // Still not found? Then try to load the (old) 64-Bit version: - if ((m_hDbhHelp == NULL) && (GetEnvironmentVariable(_T("ProgramFiles"), szTemp, 4096) > 0)) - { - _tcscat_s(szTemp, _T("\\Debugging Tools for Windows 64-Bit\\dbghelp.dll")); - if (GetFileAttributes(szTemp) != INVALID_FILE_ATTRIBUTES) - { - m_hDbhHelp = LoadLibrary(szTemp); - } - } -#endif - } - } - if (m_hDbhHelp == NULL) // if not already loaded, try to load a default-one - m_hDbhHelp = LoadLibrary(_T("dbghelp.dll")); - if (m_hDbhHelp == NULL) - return FALSE; - pSI = (tSI)GetProcAddress(m_hDbhHelp, "SymInitialize"); - pSC = (tSC)GetProcAddress(m_hDbhHelp, "SymCleanup"); - - pSW = (tSW)GetProcAddress(m_hDbhHelp, "StackWalk64"); - pSGO = (tSGO)GetProcAddress(m_hDbhHelp, "SymGetOptions"); - pSSO = (tSSO)GetProcAddress(m_hDbhHelp, "SymSetOptions"); - - pSFTA = (tSFTA)GetProcAddress(m_hDbhHelp, "SymFunctionTableAccess64"); - pSGLFA = (tSGLFA)GetProcAddress(m_hDbhHelp, "SymGetLineFromAddr64"); - pSGMB = (tSGMB)GetProcAddress(m_hDbhHelp, "SymGetModuleBase64"); - pSGMI = (tSGMI)GetProcAddress(m_hDbhHelp, "SymGetModuleInfo64"); - pSGSFA = (tSGSFA)GetProcAddress(m_hDbhHelp, "SymGetSymFromAddr64"); - pUDSN = (tUDSN)GetProcAddress(m_hDbhHelp, "UnDecorateSymbolName"); - pSLM = (tSLM)GetProcAddress(m_hDbhHelp, "SymLoadModule64"); - pSGSP = (tSGSP)GetProcAddress(m_hDbhHelp, "SymGetSearchPath"); - - if (pSC == NULL || pSFTA == NULL || pSGMB == NULL || pSGMI == NULL || pSGO == NULL || - pSGSFA == NULL || pSI == NULL || pSSO == NULL || pSW == NULL || pUDSN == NULL || - pSLM == NULL) - { - FreeLibrary(m_hDbhHelp); - m_hDbhHelp = NULL; - pSC = NULL; - return FALSE; - } - - // SymInitialize - if (this->pSI(m_hProcess, szSymPath, FALSE) == FALSE) - this->m_parent->OnDbgHelpErr("SymInitialize", GetLastError(), 0); - - DWORD symOptions = this->pSGO(); // SymGetOptions - symOptions |= SYMOPT_LOAD_LINES; - symOptions |= SYMOPT_FAIL_CRITICAL_ERRORS; - //symOptions |= SYMOPT_NO_PROMPTS; - // SymSetOptions - symOptions = this->pSSO(symOptions); - - char buf[StackWalker::STACKWALK_MAX_NAMELEN] = {0}; - if (this->pSGSP != NULL) - { - if (this->pSGSP(m_hProcess, buf, StackWalker::STACKWALK_MAX_NAMELEN) == FALSE) - this->m_parent->OnDbgHelpErr("SymGetSearchPath", GetLastError(), 0); - } - char szUserName[1024] = {0}; - DWORD dwSize = 1024; - GetUserNameA(szUserName, &dwSize); - this->m_parent->OnSymInit(buf, symOptions, szUserName); - - return TRUE; - } - - StackWalker* m_parent; - - CONTEXT m_ctx; - HMODULE m_hDbhHelp; - HANDLE m_hProcess; - -#pragma pack(push, 8) - typedef struct _IMAGEHLP_MODULE64_V3 - { - DWORD SizeOfStruct; // set to sizeof(IMAGEHLP_MODULE64) - DWORD64 BaseOfImage; // base load address of module - DWORD ImageSize; // virtual size of the loaded module - DWORD TimeDateStamp; // date/time stamp from pe header - DWORD CheckSum; // checksum from the pe header - DWORD NumSyms; // number of symbols in the symbol table - SYM_TYPE SymType; // type of symbols loaded - CHAR ModuleName[32]; // module name - CHAR ImageName[256]; // image name - CHAR LoadedImageName[256]; // symbol file name - // new elements: 07-Jun-2002 - CHAR LoadedPdbName[256]; // pdb file name - DWORD CVSig; // Signature of the CV record in the debug directories - CHAR CVData[MAX_PATH * 3]; // Contents of the CV record - DWORD PdbSig; // Signature of PDB - GUID PdbSig70; // Signature of PDB (VC 7 and up) - DWORD PdbAge; // DBI age of pdb - BOOL PdbUnmatched; // loaded an unmatched pdb - BOOL DbgUnmatched; // loaded an unmatched dbg - BOOL LineNumbers; // we have line number information - BOOL GlobalSymbols; // we have internal symbol information - BOOL TypeInfo; // we have type information - // new elements: 17-Dec-2003 - BOOL SourceIndexed; // pdb supports source server - BOOL Publics; // contains public symbols - } IMAGEHLP_MODULE64_V3, *PIMAGEHLP_MODULE64_V3; - - typedef struct _IMAGEHLP_MODULE64_V2 - { - DWORD SizeOfStruct; // set to sizeof(IMAGEHLP_MODULE64) - DWORD64 BaseOfImage; // base load address of module - DWORD ImageSize; // virtual size of the loaded module - DWORD TimeDateStamp; // date/time stamp from pe header - DWORD CheckSum; // checksum from the pe header - DWORD NumSyms; // number of symbols in the symbol table - SYM_TYPE SymType; // type of symbols loaded - CHAR ModuleName[32]; // module name - CHAR ImageName[256]; // image name - CHAR LoadedImageName[256]; // symbol file name - } IMAGEHLP_MODULE64_V2, *PIMAGEHLP_MODULE64_V2; -#pragma pack(pop) - - // SymCleanup() - typedef BOOL(__stdcall* tSC)(IN HANDLE hProcess); - tSC pSC; - - // SymFunctionTableAccess64() - typedef PVOID(__stdcall* tSFTA)(HANDLE hProcess, DWORD64 AddrBase); - tSFTA pSFTA; - - // SymGetLineFromAddr64() - typedef BOOL(__stdcall* tSGLFA)(IN HANDLE hProcess, - IN DWORD64 dwAddr, - OUT PDWORD pdwDisplacement, - OUT PIMAGEHLP_LINE64 Line); - tSGLFA pSGLFA; - - // SymGetModuleBase64() - typedef DWORD64(__stdcall* tSGMB)(IN HANDLE hProcess, IN DWORD64 dwAddr); - tSGMB pSGMB; - - // SymGetModuleInfo64() - typedef BOOL(__stdcall* tSGMI)(IN HANDLE hProcess, - IN DWORD64 dwAddr, - OUT IMAGEHLP_MODULE64_V3* ModuleInfo); - tSGMI pSGMI; - - // SymGetOptions() - typedef DWORD(__stdcall* tSGO)(VOID); - tSGO pSGO; - - // SymGetSymFromAddr64() - typedef BOOL(__stdcall* tSGSFA)(IN HANDLE hProcess, - IN DWORD64 dwAddr, - OUT PDWORD64 pdwDisplacement, - OUT PIMAGEHLP_SYMBOL64 Symbol); - tSGSFA pSGSFA; - - // SymInitialize() - typedef BOOL(__stdcall* tSI)(IN HANDLE hProcess, IN LPCSTR UserSearchPath, IN BOOL fInvadeProcess); - tSI pSI; - - // SymLoadModule64() - typedef DWORD64(__stdcall* tSLM)(IN HANDLE hProcess, - IN HANDLE hFile, - IN LPCSTR ImageName, - IN LPCSTR ModuleName, - IN DWORD64 BaseOfDll, - IN DWORD SizeOfDll); - tSLM pSLM; - - // SymSetOptions() - typedef DWORD(__stdcall* tSSO)(IN DWORD SymOptions); - tSSO pSSO; - - // StackWalk64() - typedef BOOL(__stdcall* tSW)(DWORD MachineType, - HANDLE hProcess, - HANDLE hThread, - LPSTACKFRAME64 StackFrame, - PVOID ContextRecord, - PREAD_PROCESS_MEMORY_ROUTINE64 ReadMemoryRoutine, - PFUNCTION_TABLE_ACCESS_ROUTINE64 FunctionTableAccessRoutine, - PGET_MODULE_BASE_ROUTINE64 GetModuleBaseRoutine, - PTRANSLATE_ADDRESS_ROUTINE64 TranslateAddress); - tSW pSW; - - // UnDecorateSymbolName() - typedef DWORD(__stdcall WINAPI* tUDSN)(PCSTR DecoratedName, - PSTR UnDecoratedName, - DWORD UndecoratedLength, - DWORD Flags); - tUDSN pUDSN; - - typedef BOOL(__stdcall WINAPI* tSGSP)(HANDLE hProcess, PSTR SearchPath, DWORD SearchPathLength); - tSGSP pSGSP; - -private: -// **************************************** ToolHelp32 ************************ -#define MAX_MODULE_NAME32 255 -#define TH32CS_SNAPMODULE 0x00000008 -#pragma pack(push, 8) - typedef struct tagMODULEENTRY32 - { - DWORD dwSize; - DWORD th32ModuleID; // This module - DWORD th32ProcessID; // owning process - DWORD GlblcntUsage; // Global usage count on the module - DWORD ProccntUsage; // Module usage count in th32ProcessID's context - BYTE* modBaseAddr; // Base address of module in th32ProcessID's context - DWORD modBaseSize; // Size in bytes of module starting at modBaseAddr - HMODULE hModule; // The hModule of this module in th32ProcessID's context - char szModule[MAX_MODULE_NAME32 + 1]; - char szExePath[MAX_PATH]; - } MODULEENTRY32; - typedef MODULEENTRY32* PMODULEENTRY32; - typedef MODULEENTRY32* LPMODULEENTRY32; -#pragma pack(pop) - - BOOL GetModuleListTH32(HANDLE hProcess, DWORD pid) - { - // CreateToolhelp32Snapshot() - typedef HANDLE(__stdcall * tCT32S)(DWORD dwFlags, DWORD th32ProcessID); - // Module32First() - typedef BOOL(__stdcall * tM32F)(HANDLE hSnapshot, LPMODULEENTRY32 lpme); - // Module32Next() - typedef BOOL(__stdcall * tM32N)(HANDLE hSnapshot, LPMODULEENTRY32 lpme); - - // try both dlls... - const TCHAR* dllname[] = {_T("kernel32.dll"), _T("tlhelp32.dll")}; - HINSTANCE hToolhelp = NULL; - tCT32S pCT32S = NULL; - tM32F pM32F = NULL; - tM32N pM32N = NULL; - - HANDLE hSnap; - MODULEENTRY32 me; - me.dwSize = sizeof(me); - BOOL keepGoing; - size_t i; - - for (i = 0; i < (sizeof(dllname) / sizeof(dllname[0])); i++) - { - hToolhelp = LoadLibrary(dllname[i]); - if (hToolhelp == NULL) - continue; - pCT32S = (tCT32S)GetProcAddress(hToolhelp, "CreateToolhelp32Snapshot"); - pM32F = (tM32F)GetProcAddress(hToolhelp, "Module32First"); - pM32N = (tM32N)GetProcAddress(hToolhelp, "Module32Next"); - if ((pCT32S != NULL) && (pM32F != NULL) && (pM32N != NULL)) - break; // found the functions! - FreeLibrary(hToolhelp); - hToolhelp = NULL; - } - - if (hToolhelp == NULL) - return FALSE; - - hSnap = pCT32S(TH32CS_SNAPMODULE, pid); - if (hSnap == (HANDLE)-1) - { - FreeLibrary(hToolhelp); - return FALSE; - } - - keepGoing = !!pM32F(hSnap, &me); - int cnt = 0; - while (keepGoing) - { - this->LoadModule(hProcess, me.szExePath, me.szModule, (DWORD64)me.modBaseAddr, - me.modBaseSize); - cnt++; - keepGoing = !!pM32N(hSnap, &me); - } - CloseHandle(hSnap); - FreeLibrary(hToolhelp); - if (cnt <= 0) - return FALSE; - return TRUE; - } // GetModuleListTH32 - - // **************************************** PSAPI ************************ - typedef struct _MODULEINFO - { - LPVOID lpBaseOfDll; - DWORD SizeOfImage; - LPVOID EntryPoint; - } MODULEINFO, *LPMODULEINFO; - - BOOL GetModuleListPSAPI(HANDLE hProcess) - { - // EnumProcessModules() - typedef BOOL(__stdcall * tEPM)(HANDLE hProcess, HMODULE * lphModule, DWORD cb, - LPDWORD lpcbNeeded); - // GetModuleFileNameEx() - typedef DWORD(__stdcall * tGMFNE)(HANDLE hProcess, HMODULE hModule, LPSTR lpFilename, - DWORD nSize); - // GetModuleBaseName() - typedef DWORD(__stdcall * tGMBN)(HANDLE hProcess, HMODULE hModule, LPSTR lpFilename, - DWORD nSize); - // GetModuleInformation() - typedef BOOL(__stdcall * tGMI)(HANDLE hProcess, HMODULE hModule, LPMODULEINFO pmi, DWORD nSize); - - HINSTANCE hPsapi; - tEPM pEPM; - tGMFNE pGMFNE; - tGMBN pGMBN; - tGMI pGMI; - - DWORD i; - //ModuleEntry e; - DWORD cbNeeded; - MODULEINFO mi; - HMODULE* hMods = NULL; - char* tt = NULL; - char* tt2 = NULL; - const SIZE_T TTBUFLEN = 8096; - int cnt = 0; - - hPsapi = LoadLibrary(_T("psapi.dll")); - if (hPsapi == NULL) - return FALSE; - - pEPM = (tEPM)GetProcAddress(hPsapi, "EnumProcessModules"); - pGMFNE = (tGMFNE)GetProcAddress(hPsapi, "GetModuleFileNameExA"); - pGMBN = (tGMFNE)GetProcAddress(hPsapi, "GetModuleBaseNameA"); - pGMI = (tGMI)GetProcAddress(hPsapi, "GetModuleInformation"); - if ((pEPM == NULL) || (pGMFNE == NULL) || (pGMBN == NULL) || (pGMI == NULL)) - { - // we couldn't find all functions - FreeLibrary(hPsapi); - return FALSE; - } - - hMods = (HMODULE*)malloc(sizeof(HMODULE) * (TTBUFLEN / sizeof(HMODULE))); - tt = (char*)malloc(sizeof(char) * TTBUFLEN); - tt2 = (char*)malloc(sizeof(char) * TTBUFLEN); - if ((hMods == NULL) || (tt == NULL) || (tt2 == NULL)) - goto cleanup; - - if (!pEPM(hProcess, hMods, TTBUFLEN, &cbNeeded)) - { - //_ftprintf(fLogFile, _T("%lu: EPM failed, GetLastError = %lu\n"), g_dwShowCount, gle ); - goto cleanup; - } - - if (cbNeeded > TTBUFLEN) - { - //_ftprintf(fLogFile, _T("%lu: More than %lu module handles. Huh?\n"), g_dwShowCount, lenof( hMods ) ); - goto cleanup; - } - - for (i = 0; i < cbNeeded / sizeof(hMods[0]); i++) - { - // base address, size - pGMI(hProcess, hMods[i], &mi, sizeof(mi)); - // image file name - tt[0] = 0; - pGMFNE(hProcess, hMods[i], tt, TTBUFLEN); - // module name - tt2[0] = 0; - pGMBN(hProcess, hMods[i], tt2, TTBUFLEN); - - DWORD dwRes = this->LoadModule(hProcess, tt, tt2, (DWORD64)mi.lpBaseOfDll, mi.SizeOfImage); - if (dwRes != ERROR_SUCCESS) - this->m_parent->OnDbgHelpErr("LoadModule", dwRes, 0); - cnt++; - } - - cleanup: - if (hPsapi != NULL) - FreeLibrary(hPsapi); - if (tt2 != NULL) - free(tt2); - if (tt != NULL) - free(tt); - if (hMods != NULL) - free(hMods); - - return cnt != 0; - } // GetModuleListPSAPI - - DWORD LoadModule(HANDLE hProcess, LPCSTR img, LPCSTR mod, DWORD64 baseAddr, DWORD size) - { - CHAR* szImg = _strdup(img); - CHAR* szMod = _strdup(mod); - DWORD result = ERROR_SUCCESS; - if ((szImg == NULL) || (szMod == NULL)) - result = ERROR_NOT_ENOUGH_MEMORY; - else - { - if (pSLM(hProcess, 0, szImg, szMod, baseAddr, size) == 0) - result = GetLastError(); - } - ULONGLONG fileVersion = 0; - if ((m_parent != NULL) && (szImg != NULL)) - { - // try to retrieve the file-version: - if ((this->m_parent->m_options & StackWalker::RetrieveFileVersion) != 0) - { - VS_FIXEDFILEINFO* fInfo = NULL; - DWORD dwHandle; - DWORD dwSize = GetFileVersionInfoSizeA(szImg, &dwHandle); - if (dwSize > 0) - { - LPVOID vData = malloc(dwSize); - if (vData != NULL) - { - if (GetFileVersionInfoA(szImg, dwHandle, dwSize, vData) != 0) - { - UINT len; - TCHAR szSubBlock[] = _T("\\"); - if (VerQueryValue(vData, szSubBlock, (LPVOID*)&fInfo, &len) == 0) - fInfo = NULL; - else - { - fileVersion = - ((ULONGLONG)fInfo->dwFileVersionLS) + ((ULONGLONG)fInfo->dwFileVersionMS << 32); - } - } - free(vData); - } - } - } - - // Retrieve some additional-infos about the module - IMAGEHLP_MODULE64_V3 Module; - const char* szSymType = "-unknown-"; - if (this->GetModuleInfo(hProcess, baseAddr, &Module) != FALSE) - { - switch (Module.SymType) - { - case SymNone: - szSymType = "-nosymbols-"; - break; - case SymCoff: // 1 - szSymType = "COFF"; - break; - case SymCv: // 2 - szSymType = "CV"; - break; - case SymPdb: // 3 - szSymType = "PDB"; - break; - case SymExport: // 4 - szSymType = "-exported-"; - break; - case SymDeferred: // 5 - szSymType = "-deferred-"; - break; - case SymSym: // 6 - szSymType = "SYM"; - break; - case 7: // SymDia: - szSymType = "DIA"; - break; - case 8: //SymVirtual: - szSymType = "Virtual"; - break; - } - } - LPCSTR pdbName = Module.LoadedImageName; - if (Module.LoadedPdbName[0] != 0) - pdbName = Module.LoadedPdbName; - this->m_parent->OnLoadModule(img, mod, baseAddr, size, result, szSymType, pdbName, - fileVersion); - } - if (szImg != NULL) - free(szImg); - if (szMod != NULL) - free(szMod); - return result; - } - -public: - BOOL LoadModules(HANDLE hProcess, DWORD dwProcessId) - { - // first try toolhelp32 - if (GetModuleListTH32(hProcess, dwProcessId)) - return true; - // then try psapi - return GetModuleListPSAPI(hProcess); - } - - BOOL GetModuleInfo(HANDLE hProcess, DWORD64 baseAddr, IMAGEHLP_MODULE64_V3* pModuleInfo) - { - memset(pModuleInfo, 0, sizeof(IMAGEHLP_MODULE64_V3)); - if (this->pSGMI == NULL) - { - SetLastError(ERROR_DLL_INIT_FAILED); - return FALSE; - } - // First try to use the larger ModuleInfo-Structure - pModuleInfo->SizeOfStruct = sizeof(IMAGEHLP_MODULE64_V3); - void* pData = malloc( - 4096); // reserve enough memory, so the bug in v6.3.5.1 does not lead to memory-overwrites... - if (pData == NULL) - { - SetLastError(ERROR_NOT_ENOUGH_MEMORY); - return FALSE; - } - memcpy(pData, pModuleInfo, sizeof(IMAGEHLP_MODULE64_V3)); - static bool s_useV3Version = true; - if (s_useV3Version) - { - if (this->pSGMI(hProcess, baseAddr, (IMAGEHLP_MODULE64_V3*)pData) != FALSE) - { - // only copy as much memory as is reserved... - memcpy(pModuleInfo, pData, sizeof(IMAGEHLP_MODULE64_V3)); - pModuleInfo->SizeOfStruct = sizeof(IMAGEHLP_MODULE64_V3); - free(pData); - return TRUE; - } - s_useV3Version = false; // to prevent unnecessary calls with the larger struct... - } - - // could not retrieve the bigger structure, try with the smaller one (as defined in VC7.1)... - pModuleInfo->SizeOfStruct = sizeof(IMAGEHLP_MODULE64_V2); - memcpy(pData, pModuleInfo, sizeof(IMAGEHLP_MODULE64_V2)); - if (this->pSGMI(hProcess, baseAddr, (IMAGEHLP_MODULE64_V3*)pData) != FALSE) - { - // only copy as much memory as is reserved... - memcpy(pModuleInfo, pData, sizeof(IMAGEHLP_MODULE64_V2)); - pModuleInfo->SizeOfStruct = sizeof(IMAGEHLP_MODULE64_V2); - free(pData); - return TRUE; - } - free(pData); - SetLastError(ERROR_DLL_INIT_FAILED); - return FALSE; - } -}; - -// ############################################################# - -#if defined(_MSC_VER) && _MSC_VER >= 1400 && _MSC_VER < 1900 -extern "C" void* __cdecl _getptd(); -#endif -#if defined(_MSC_VER) && _MSC_VER >= 1900 -extern "C" void** __cdecl __current_exception_context(); -#endif - -static PCONTEXT get_current_exception_context() -{ - PCONTEXT * pctx = NULL; -#if defined(_MSC_VER) && _MSC_VER >= 1400 && _MSC_VER < 1900 - LPSTR ptd = (LPSTR)_getptd(); - if (ptd) - pctx = (PCONTEXT *)(ptd + (sizeof(void*) == 4 ? 0x8C : 0xF8)); -#endif -#if defined(_MSC_VER) && _MSC_VER >= 1900 - pctx = (PCONTEXT *)__current_exception_context(); -#endif - return pctx ? *pctx : NULL; -} - -bool StackWalker::Init(ExceptType extype, int options, LPCSTR szSymPath, DWORD dwProcessId, - HANDLE hProcess, PEXCEPTION_POINTERS exp) -{ - PCONTEXT ctx = NULL; - if (extype == AfterCatch) - ctx = get_current_exception_context(); - if (extype == AfterExcept && exp) - ctx = exp->ContextRecord; - this->m_options = options; - this->m_modulesLoaded = FALSE; - this->m_szSymPath = NULL; - this->m_MaxRecursionCount = 1000; - this->m_sw = NULL; - SetTargetProcess(dwProcessId, hProcess); - SetSymPath(szSymPath); - /* MSVC ignore std::nothrow specifier for `new` operator */ - LPVOID buf = malloc(sizeof(StackWalkerInternal)); - if (!buf) - return false; - memset(buf, 0, sizeof(StackWalkerInternal)); - this->m_sw = new(buf) StackWalkerInternal(this, this->m_hProcess, ctx); // placement new - return true; -} - -StackWalker::StackWalker(DWORD dwProcessId, HANDLE hProcess) -{ - Init(NonExcept, OptionsAll, NULL, dwProcessId, hProcess); -} - -StackWalker::StackWalker(int options, LPCSTR szSymPath, DWORD dwProcessId, HANDLE hProcess) -{ - Init(NonExcept, options, szSymPath, dwProcessId, hProcess); -} - -StackWalker::StackWalker(ExceptType extype, int options, PEXCEPTION_POINTERS exp) -{ - Init(extype, options, NULL, GetCurrentProcessId(), GetCurrentProcess(), exp); -} - -StackWalker::~StackWalker() -{ - SetSymPath(NULL); - if (m_sw != NULL) { - m_sw->~StackWalkerInternal(); // call the object's destructor - free(m_sw); - } - m_sw = NULL; -} - -bool StackWalker::SetSymPath(LPCSTR szSymPath) -{ - if (m_szSymPath) - free(m_szSymPath); - m_szSymPath = NULL; - if (szSymPath == NULL) - return true; - m_szSymPath = _strdup(szSymPath); - if (m_szSymPath) - m_options |= SymBuildPath; - return true; -} - -bool StackWalker::SetTargetProcess(DWORD dwProcessId, HANDLE hProcess) -{ - m_dwProcessId = dwProcessId; - m_hProcess = hProcess; - if (m_sw) - m_sw->m_hProcess = hProcess; - return true; -} - -PCONTEXT StackWalker::GetCurrentExceptionContext() -{ - return get_current_exception_context(); -} - -BOOL StackWalker::LoadModules() -{ - if (this->m_sw == NULL) - { - SetLastError(ERROR_DLL_INIT_FAILED); - return FALSE; - } - if (m_modulesLoaded != FALSE) - return TRUE; - - // Build the sym-path: - char* szSymPath = NULL; - if ((this->m_options & SymBuildPath) != 0) - { - const size_t nSymPathLen = 4096; - szSymPath = (char*)malloc(nSymPathLen); - if (szSymPath == NULL) - { - SetLastError(ERROR_NOT_ENOUGH_MEMORY); - return FALSE; - } - szSymPath[0] = 0; - // Now first add the (optional) provided sympath: - if (this->m_szSymPath != NULL) - { - strcat_s(szSymPath, nSymPathLen, this->m_szSymPath); - strcat_s(szSymPath, nSymPathLen, ";"); - } - - strcat_s(szSymPath, nSymPathLen, ".;"); - - const size_t nTempLen = 1024; - char szTemp[nTempLen]; - // Now add the current directory: - if (GetCurrentDirectoryA(nTempLen, szTemp) > 0) - { - szTemp[nTempLen - 1] = 0; - strcat_s(szSymPath, nSymPathLen, szTemp); - strcat_s(szSymPath, nSymPathLen, ";"); - } - - // Now add the path for the main-module: - if (GetModuleFileNameA(NULL, szTemp, nTempLen) > 0) - { - szTemp[nTempLen - 1] = 0; - for (char* p = (szTemp + strlen(szTemp) - 1); p >= szTemp; --p) - { - // locate the rightmost path separator - if ((*p == '\\') || (*p == '/') || (*p == ':')) - { - *p = 0; - break; - } - } // for (search for path separator...) - if (strlen(szTemp) > 0) - { - strcat_s(szSymPath, nSymPathLen, szTemp); - strcat_s(szSymPath, nSymPathLen, ";"); - } - } - if (GetEnvironmentVariableA("_NT_SYMBOL_PATH", szTemp, nTempLen) > 0) - { - szTemp[nTempLen - 1] = 0; - strcat_s(szSymPath, nSymPathLen, szTemp); - strcat_s(szSymPath, nSymPathLen, ";"); - } - if (GetEnvironmentVariableA("_NT_ALTERNATE_SYMBOL_PATH", szTemp, nTempLen) > 0) - { - szTemp[nTempLen - 1] = 0; - strcat_s(szSymPath, nSymPathLen, szTemp); - strcat_s(szSymPath, nSymPathLen, ";"); - } - if (GetEnvironmentVariableA("SYSTEMROOT", szTemp, nTempLen) > 0) - { - szTemp[nTempLen - 1] = 0; - strcat_s(szSymPath, nSymPathLen, szTemp); - strcat_s(szSymPath, nSymPathLen, ";"); - // also add the "system32"-directory: - strcat_s(szTemp, nTempLen, "\\system32"); - strcat_s(szSymPath, nSymPathLen, szTemp); - strcat_s(szSymPath, nSymPathLen, ";"); - } - - if ((this->m_options & SymUseSymSrv) != 0) - { - if (GetEnvironmentVariableA("SYSTEMDRIVE", szTemp, nTempLen) > 0) - { - szTemp[nTempLen - 1] = 0; - strcat_s(szSymPath, nSymPathLen, "SRV*"); - strcat_s(szSymPath, nSymPathLen, szTemp); - strcat_s(szSymPath, nSymPathLen, "\\websymbols"); - strcat_s(szSymPath, nSymPathLen, "*https://msdl.microsoft.com/download/symbols;"); - } - else - strcat_s(szSymPath, nSymPathLen, - "SRV*c:\\websymbols*https://msdl.microsoft.com/download/symbols;"); - } - } // if SymBuildPath - - // First Init the whole stuff... - BOOL bRet = this->m_sw->Init(szSymPath); - if (szSymPath != NULL) - free(szSymPath); - szSymPath = NULL; - if (bRet == FALSE) - { - this->OnDbgHelpErr("Error while initializing dbghelp.dll", 0, 0); - SetLastError(ERROR_DLL_INIT_FAILED); - return FALSE; - } - - bRet = this->m_sw->LoadModules(this->m_hProcess, this->m_dwProcessId); - if (bRet != FALSE) - m_modulesLoaded = TRUE; - return bRet; -} - -// The following is used to pass the "userData"-Pointer to the user-provided readMemoryFunction -// This has to be done due to a problem with the "hProcess"-parameter in x64... -// Because this class is in no case multi-threading-enabled (because of the limitations -// of dbghelp.dll) it is "safe" to use a static-variable -static StackWalker::PReadProcessMemoryRoutine s_readMemoryFunction = NULL; -static LPVOID s_readMemoryFunction_UserData = NULL; - -BOOL StackWalker::ShowCallstack(HANDLE hThread, - const CONTEXT* context, - PReadProcessMemoryRoutine readMemoryFunction, - LPVOID pUserData) -{ - CONTEXT c; - CallstackEntry csEntry; - IMAGEHLP_SYMBOL64* pSym = NULL; - StackWalkerInternal::IMAGEHLP_MODULE64_V3 Module; - IMAGEHLP_LINE64 Line; - int frameNum; - bool bLastEntryCalled = true; - int curRecursionCount = 0; - - if (m_modulesLoaded == FALSE) - this->LoadModules(); // ignore the result... - - if (this->m_sw->m_hDbhHelp == NULL) - { - SetLastError(ERROR_DLL_INIT_FAILED); - return FALSE; - } - - s_readMemoryFunction = readMemoryFunction; - s_readMemoryFunction_UserData = pUserData; - - if (context == NULL) - { - // If no context is provided, capture the context - // See: https://stackwalker.codeplex.com/discussions/446958 -#if _WIN32_WINNT <= 0x0501 - // If we need to support XP, we need to use the "old way", because "GetThreadId" is not available! - if (hThread == GetCurrentThread()) -#else - if (GetThreadId(hThread) == GetCurrentThreadId()) -#endif - { - if (m_sw->m_ctx.ContextFlags != 0) - c = m_sw->m_ctx; // context taken at Init - else - GET_CURRENT_CONTEXT_STACKWALKER_CODEPLEX(c, USED_CONTEXT_FLAGS); - } - else - { - SuspendThread(hThread); - memset(&c, 0, sizeof(CONTEXT)); - c.ContextFlags = USED_CONTEXT_FLAGS; - - // TODO: Detect if you want to get a thread context of a different process, which is running a different processor architecture... - // This does only work if we are x64 and the target process is x64 or x86; - // It cannot work, if this process is x64 and the target process is x64... this is not supported... - // See also: http://www.howzatt.demon.co.uk/articles/DebuggingInWin64.html - if (GetThreadContext(hThread, &c) == FALSE) - { - ResumeThread(hThread); - return FALSE; - } - } - } - else - c = *context; - - // init STACKFRAME for first call - STACKFRAME64 s; // in/out stackframe - memset(&s, 0, sizeof(s)); - DWORD imageType; -#ifdef _M_IX86 - // normally, call ImageNtHeader() and use machine info from PE header - imageType = IMAGE_FILE_MACHINE_I386; - s.AddrPC.Offset = c.Eip; - s.AddrPC.Mode = AddrModeFlat; - s.AddrFrame.Offset = c.Ebp; - s.AddrFrame.Mode = AddrModeFlat; - s.AddrStack.Offset = c.Esp; - s.AddrStack.Mode = AddrModeFlat; -#elif _M_X64 - imageType = IMAGE_FILE_MACHINE_AMD64; - s.AddrPC.Offset = c.Rip; - s.AddrPC.Mode = AddrModeFlat; - s.AddrFrame.Offset = c.Rsp; - s.AddrFrame.Mode = AddrModeFlat; - s.AddrStack.Offset = c.Rsp; - s.AddrStack.Mode = AddrModeFlat; -#elif _M_IA64 - imageType = IMAGE_FILE_MACHINE_IA64; - s.AddrPC.Offset = c.StIIP; - s.AddrPC.Mode = AddrModeFlat; - s.AddrFrame.Offset = c.IntSp; - s.AddrFrame.Mode = AddrModeFlat; - s.AddrBStore.Offset = c.RsBSP; - s.AddrBStore.Mode = AddrModeFlat; - s.AddrStack.Offset = c.IntSp; - s.AddrStack.Mode = AddrModeFlat; -#elif _M_ARM64 - imageType = IMAGE_FILE_MACHINE_ARM64; - s.AddrPC.Offset = c.Pc; - s.AddrPC.Mode = AddrModeFlat; - s.AddrFrame.Offset = c.Fp; - s.AddrFrame.Mode = AddrModeFlat; - s.AddrStack.Offset = c.Sp; - s.AddrStack.Mode = AddrModeFlat; -#else -#error "Platform not supported!" -#endif - - pSym = (IMAGEHLP_SYMBOL64*)malloc(sizeof(IMAGEHLP_SYMBOL64) + STACKWALK_MAX_NAMELEN); - if (!pSym) - goto cleanup; // not enough memory... - memset(pSym, 0, sizeof(IMAGEHLP_SYMBOL64) + STACKWALK_MAX_NAMELEN); - pSym->SizeOfStruct = sizeof(IMAGEHLP_SYMBOL64); - pSym->MaxNameLength = STACKWALK_MAX_NAMELEN; - - memset(&Line, 0, sizeof(Line)); - Line.SizeOfStruct = sizeof(Line); - - memset(&Module, 0, sizeof(Module)); - Module.SizeOfStruct = sizeof(Module); - - for (frameNum = 0;; ++frameNum) - { - // get next stack frame (StackWalk64(), SymFunctionTableAccess64(), SymGetModuleBase64()) - // if this returns ERROR_INVALID_ADDRESS (487) or ERROR_NOACCESS (998), you can - // assume that either you are done, or that the stack is so hosed that the next - // deeper frame could not be found. - // CONTEXT need not to be supplied if imageTyp is IMAGE_FILE_MACHINE_I386! - if (!this->m_sw->pSW(imageType, this->m_hProcess, hThread, &s, &c, myReadProcMem, - this->m_sw->pSFTA, this->m_sw->pSGMB, NULL)) - { - // INFO: "StackWalk64" does not set "GetLastError"... - this->OnDbgHelpErr("StackWalk64", 0, s.AddrPC.Offset); - break; - } - - csEntry.offset = s.AddrPC.Offset; - csEntry.name[0] = 0; - csEntry.undName[0] = 0; - csEntry.undFullName[0] = 0; - csEntry.offsetFromSmybol = 0; - csEntry.offsetFromLine = 0; - csEntry.lineFileName[0] = 0; - csEntry.lineNumber = 0; - csEntry.loadedImageName[0] = 0; - csEntry.moduleName[0] = 0; - if (s.AddrPC.Offset == s.AddrReturn.Offset) - { - if ((this->m_MaxRecursionCount > 0) && (curRecursionCount > m_MaxRecursionCount)) - { - this->OnDbgHelpErr("StackWalk64-Endless-Callstack!", 0, s.AddrPC.Offset); - break; - } - curRecursionCount++; - } - else - curRecursionCount = 0; - if (s.AddrPC.Offset != 0) - { - // we seem to have a valid PC - // show procedure info (SymGetSymFromAddr64()) - if (this->m_sw->pSGSFA(this->m_hProcess, s.AddrPC.Offset, &(csEntry.offsetFromSmybol), - pSym) != FALSE) - { - MyStrCpy(csEntry.name, STACKWALK_MAX_NAMELEN, pSym->Name); - // UnDecorateSymbolName() - this->m_sw->pUDSN(pSym->Name, csEntry.undName, STACKWALK_MAX_NAMELEN, UNDNAME_NAME_ONLY); - this->m_sw->pUDSN(pSym->Name, csEntry.undFullName, STACKWALK_MAX_NAMELEN, UNDNAME_COMPLETE); - } - else - { - this->OnDbgHelpErr("SymGetSymFromAddr64", GetLastError(), s.AddrPC.Offset); - } - - // show line number info, NT5.0-method (SymGetLineFromAddr64()) - if (this->m_sw->pSGLFA != NULL) - { // yes, we have SymGetLineFromAddr64() - if (this->m_sw->pSGLFA(this->m_hProcess, s.AddrPC.Offset, &(csEntry.offsetFromLine), - &Line) != FALSE) - { - csEntry.lineNumber = Line.LineNumber; - MyStrCpy(csEntry.lineFileName, STACKWALK_MAX_NAMELEN, Line.FileName); - } - else - { - this->OnDbgHelpErr("SymGetLineFromAddr64", GetLastError(), s.AddrPC.Offset); - } - } // yes, we have SymGetLineFromAddr64() - - // show module info (SymGetModuleInfo64()) - if (this->m_sw->GetModuleInfo(this->m_hProcess, s.AddrPC.Offset, &Module) != FALSE) - { // got module info OK - switch (Module.SymType) - { - case SymNone: - csEntry.symTypeString = "-nosymbols-"; - break; - case SymCoff: - csEntry.symTypeString = "COFF"; - break; - case SymCv: - csEntry.symTypeString = "CV"; - break; - case SymPdb: - csEntry.symTypeString = "PDB"; - break; - case SymExport: - csEntry.symTypeString = "-exported-"; - break; - case SymDeferred: - csEntry.symTypeString = "-deferred-"; - break; - case SymSym: - csEntry.symTypeString = "SYM"; - break; -#if API_VERSION_NUMBER >= 9 - case SymDia: - csEntry.symTypeString = "DIA"; - break; -#endif - case 8: //SymVirtual: - csEntry.symTypeString = "Virtual"; - break; - default: - //_snprintf( ty, sizeof(ty), "symtype=%ld", (long) Module.SymType ); - csEntry.symTypeString = NULL; - break; - } - - MyStrCpy(csEntry.moduleName, STACKWALK_MAX_NAMELEN, Module.ModuleName); - csEntry.baseOfImage = Module.BaseOfImage; - MyStrCpy(csEntry.loadedImageName, STACKWALK_MAX_NAMELEN, Module.LoadedImageName); - } // got module info OK - else - { - this->OnDbgHelpErr("SymGetModuleInfo64", GetLastError(), s.AddrPC.Offset); - } - } // we seem to have a valid PC - - CallstackEntryType et = nextEntry; - if (frameNum == 0) - et = firstEntry; - bLastEntryCalled = false; - this->OnCallstackEntry(et, csEntry); - - if (s.AddrReturn.Offset == 0) - { - bLastEntryCalled = true; - this->OnCallstackEntry(lastEntry, csEntry); - SetLastError(ERROR_SUCCESS); - break; - } - } // for ( frameNum ) - -cleanup: - if (pSym) - free(pSym); - - if (bLastEntryCalled == false) - this->OnCallstackEntry(lastEntry, csEntry); - - if (context == NULL) - ResumeThread(hThread); - - return TRUE; -} - -BOOL StackWalker::ShowObject(LPVOID pObject) -{ - // Load modules if not done yet - if (m_modulesLoaded == FALSE) - this->LoadModules(); // ignore the result... - - // Verify that the DebugHelp.dll was actually found - if (this->m_sw->m_hDbhHelp == NULL) - { - SetLastError(ERROR_DLL_INIT_FAILED); - return FALSE; - } - - // SymGetSymFromAddr64() is required - if (this->m_sw->pSGSFA == NULL) - return FALSE; - - // Show object info (SymGetSymFromAddr64()) - DWORD64 dwAddress = DWORD64(pObject); - DWORD64 dwDisplacement = 0; - const SIZE_T symSize = sizeof(IMAGEHLP_SYMBOL64) + STACKWALK_MAX_NAMELEN; - IMAGEHLP_SYMBOL64* pSym = (IMAGEHLP_SYMBOL64*) malloc(symSize); - if (!pSym) - return FALSE; - memset(pSym, 0, symSize); - pSym->SizeOfStruct = sizeof(IMAGEHLP_SYMBOL64); - pSym->MaxNameLength = STACKWALK_MAX_NAMELEN; - if (this->m_sw->pSGSFA(this->m_hProcess, dwAddress, &dwDisplacement, pSym) == FALSE) - { - this->OnDbgHelpErr("SymGetSymFromAddr64", GetLastError(), dwAddress); - return FALSE; - } - // Object name output - this->OnOutput(pSym->Name); - - free(pSym); - return TRUE; -}; - -BOOL __stdcall StackWalker::myReadProcMem(HANDLE hProcess, - DWORD64 qwBaseAddress, - PVOID lpBuffer, - DWORD nSize, - LPDWORD lpNumberOfBytesRead) -{ - if (s_readMemoryFunction == NULL) - { - SIZE_T st; - BOOL bRet = ReadProcessMemory(hProcess, (LPVOID)qwBaseAddress, lpBuffer, nSize, &st); - *lpNumberOfBytesRead = (DWORD)st; - //printf("ReadMemory: hProcess: %p, baseAddr: %p, buffer: %p, size: %d, read: %d, result: %d\n", hProcess, (LPVOID) qwBaseAddress, lpBuffer, nSize, (DWORD) st, (DWORD) bRet); - return bRet; - } - else - { - return s_readMemoryFunction(hProcess, qwBaseAddress, lpBuffer, nSize, lpNumberOfBytesRead, - s_readMemoryFunction_UserData); - } -} - -void StackWalker::OnLoadModule(LPCSTR img, - LPCSTR mod, - DWORD64 baseAddr, - DWORD size, - DWORD result, - LPCSTR symType, - LPCSTR pdbName, - ULONGLONG fileVersion) -{ - CHAR buffer[STACKWALK_MAX_NAMELEN]; - size_t maxLen = STACKWALK_MAX_NAMELEN; -#if _MSC_VER >= 1400 - maxLen = _TRUNCATE; -#endif - if (fileVersion == 0) - _snprintf_s(buffer, maxLen, "%s:%s (%p), size: %d (result: %d), SymType: '%s', PDB: '%s'\n", - img, mod, (LPVOID)baseAddr, size, result, symType, pdbName); - else - { - DWORD v4 = (DWORD)(fileVersion & 0xFFFF); - DWORD v3 = (DWORD)((fileVersion >> 16) & 0xFFFF); - DWORD v2 = (DWORD)((fileVersion >> 32) & 0xFFFF); - DWORD v1 = (DWORD)((fileVersion >> 48) & 0xFFFF); - _snprintf_s( - buffer, maxLen, - "%s:%s (%p), size: %d (result: %d), SymType: '%s', PDB: '%s', fileVersion: %d.%d.%d.%d\n", - img, mod, (LPVOID)baseAddr, size, result, symType, pdbName, v1, v2, v3, v4); - } - buffer[STACKWALK_MAX_NAMELEN - 1] = 0; // be sure it is NULL terminated - OnOutput(buffer); -} - -void StackWalker::OnCallstackEntry(CallstackEntryType eType, CallstackEntry& entry) -{ - CHAR buffer[STACKWALK_MAX_NAMELEN]; - size_t maxLen = STACKWALK_MAX_NAMELEN; -#if _MSC_VER >= 1400 - maxLen = _TRUNCATE; -#endif - if ((eType != lastEntry) && (entry.offset != 0)) - { - if (entry.name[0] == 0) - MyStrCpy(entry.name, STACKWALK_MAX_NAMELEN, "(function-name not available)"); - if (entry.undName[0] != 0) - MyStrCpy(entry.name, STACKWALK_MAX_NAMELEN, entry.undName); - if (entry.undFullName[0] != 0) - MyStrCpy(entry.name, STACKWALK_MAX_NAMELEN, entry.undFullName); - if (entry.lineFileName[0] == 0) - { - MyStrCpy(entry.lineFileName, STACKWALK_MAX_NAMELEN, "(filename not available)"); - if (entry.moduleName[0] == 0) - MyStrCpy(entry.moduleName, STACKWALK_MAX_NAMELEN, "(module-name not available)"); - _snprintf_s(buffer, maxLen, "%p (%s): %s: %s\n", (LPVOID)entry.offset, entry.moduleName, - entry.lineFileName, entry.name); - } - else - _snprintf_s(buffer, maxLen, "%s (%d): %s\n", entry.lineFileName, entry.lineNumber, - entry.name); - buffer[STACKWALK_MAX_NAMELEN - 1] = 0; - OnOutput(buffer); - } -} - -void StackWalker::OnDbgHelpErr(LPCSTR szFuncName, DWORD gle, DWORD64 addr) -{ - CHAR buffer[STACKWALK_MAX_NAMELEN]; - size_t maxLen = STACKWALK_MAX_NAMELEN; -#if _MSC_VER >= 1400 - maxLen = _TRUNCATE; -#endif - _snprintf_s(buffer, maxLen, "ERROR: %s, GetLastError: %d (Address: %p)\n", szFuncName, gle, - (LPVOID)addr); - buffer[STACKWALK_MAX_NAMELEN - 1] = 0; - OnOutput(buffer); -} - -void StackWalker::OnSymInit(LPCSTR szSearchPath, DWORD symOptions, LPCSTR szUserName) -{ - CHAR buffer[STACKWALK_MAX_NAMELEN]; - size_t maxLen = STACKWALK_MAX_NAMELEN; -#if _MSC_VER >= 1400 - maxLen = _TRUNCATE; -#endif - _snprintf_s(buffer, maxLen, "SymInit: Symbol-SearchPath: '%s', symOptions: %d, UserName: '%s'\n", - szSearchPath, symOptions, szUserName); - buffer[STACKWALK_MAX_NAMELEN - 1] = 0; - OnOutput(buffer); - // Also display the OS-version -#if _MSC_VER <= 1200 - OSVERSIONINFOA ver; - ZeroMemory(&ver, sizeof(OSVERSIONINFOA)); - ver.dwOSVersionInfoSize = sizeof(ver); - if (GetVersionExA(&ver) != FALSE) - { - _snprintf_s(buffer, maxLen, "OS-Version: %d.%d.%d (%s)\n", ver.dwMajorVersion, - ver.dwMinorVersion, ver.dwBuildNumber, ver.szCSDVersion); - buffer[STACKWALK_MAX_NAMELEN - 1] = 0; - OnOutput(buffer); - } -#else - OSVERSIONINFOEXA ver; - ZeroMemory(&ver, sizeof(OSVERSIONINFOEXA)); - ver.dwOSVersionInfoSize = sizeof(ver); -#if _MSC_VER >= 1900 -#pragma warning(push) -#pragma warning(disable : 4996) -#endif - if (GetVersionExA((OSVERSIONINFOA*)&ver) != FALSE) - { - _snprintf_s(buffer, maxLen, "OS-Version: %d.%d.%d (%s) 0x%x-0x%x\n", ver.dwMajorVersion, - ver.dwMinorVersion, ver.dwBuildNumber, ver.szCSDVersion, ver.wSuiteMask, - ver.wProductType); - buffer[STACKWALK_MAX_NAMELEN - 1] = 0; - OnOutput(buffer); - } -#if _MSC_VER >= 1900 -#pragma warning(pop) -#endif -#endif -} - -void StackWalker::OnOutput(LPCSTR buffer) -{ - OutputDebugStringA(buffer); -} diff --git a/wpiutil/src/main/native/windows/StackWalker.h b/wpiutil/src/main/native/windows/StackWalker.h deleted file mode 100644 index 5ab241ec13..0000000000 --- a/wpiutil/src/main/native/windows/StackWalker.h +++ /dev/null @@ -1,273 +0,0 @@ -#ifndef __STACKWALKER_H__ -#define __STACKWALKER_H__ - -#if defined(_MSC_VER) - -/********************************************************************** - * - * StackWalker.h - * - * - * - * LICENSE (http://www.opensource.org/licenses/bsd-license.php) - * - * Copyright (c) 2005-2009, Jochen Kalmbach - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * - * Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * Neither the name of Jochen Kalmbach nor the names of its contributors may be - * used to endorse or promote products derived from this software without - * specific prior written permission. - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, - * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND - * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - * **********************************************************************/ -// #pragma once is supported starting with _MSC_VER 1000, -// so we need not to check the version (because we only support _MSC_VER >= 1100)! -#pragma once - -#include - -// special defines for VC5/6 (if no actual PSDK is installed): -#if _MSC_VER < 1300 -typedef unsigned __int64 DWORD64, *PDWORD64; -#if defined(_WIN64) -typedef unsigned __int64 SIZE_T, *PSIZE_T; -#else -typedef unsigned long SIZE_T, *PSIZE_T; -#endif -#endif // _MSC_VER < 1300 - -class StackWalkerInternal; // forward -class StackWalker -{ -public: - typedef enum ExceptType - { - NonExcept = 0, // RtlCaptureContext - AfterExcept = 1, - AfterCatch = 2, // get_current_exception_context - } ExceptType; - - typedef enum StackWalkOptions - { - // No addition info will be retrieved - // (only the address is available) - RetrieveNone = 0, - - // Try to get the symbol-name - RetrieveSymbol = 1, - - // Try to get the line for this symbol - RetrieveLine = 2, - - // Try to retrieve the module-infos - RetrieveModuleInfo = 4, - - // Also retrieve the version for the DLL/EXE - RetrieveFileVersion = 8, - - // Contains all the above - RetrieveVerbose = 0xF, - - // Generate a "good" symbol-search-path - SymBuildPath = 0x10, - - // Also use the public Microsoft-Symbol-Server - SymUseSymSrv = 0x20, - - // Contains all the above "Sym"-options - SymAll = 0x30, - - // Contains all options (default) - OptionsAll = 0x3F - } StackWalkOptions; - - StackWalker(ExceptType extype, int options = OptionsAll, PEXCEPTION_POINTERS exp = NULL); - - StackWalker(int options = OptionsAll, // 'int' is by design, to combine the enum-flags - LPCSTR szSymPath = NULL, - DWORD dwProcessId = GetCurrentProcessId(), - HANDLE hProcess = GetCurrentProcess()); - - StackWalker(DWORD dwProcessId, HANDLE hProcess); - - virtual ~StackWalker(); - - bool SetSymPath(LPCSTR szSymPath); - - bool SetTargetProcess(DWORD dwProcessId, HANDLE hProcess); - - PCONTEXT GetCurrentExceptionContext(); - -private: - bool Init(ExceptType extype, int options, LPCSTR szSymPath, DWORD dwProcessId, - HANDLE hProcess, PEXCEPTION_POINTERS exp = NULL); - -public: - typedef BOOL(__stdcall* PReadProcessMemoryRoutine)( - HANDLE hProcess, - DWORD64 qwBaseAddress, - PVOID lpBuffer, - DWORD nSize, - LPDWORD lpNumberOfBytesRead, - LPVOID pUserData // optional data, which was passed in "ShowCallstack" - ); - - BOOL LoadModules(); - - BOOL ShowCallstack( - HANDLE hThread = GetCurrentThread(), - const CONTEXT* context = NULL, - PReadProcessMemoryRoutine readMemoryFunction = NULL, - LPVOID pUserData = NULL // optional to identify some data in the 'readMemoryFunction'-callback - ); - - BOOL ShowObject(LPVOID pObject); - -#if _MSC_VER >= 1300 - // due to some reasons, the "STACKWALK_MAX_NAMELEN" must be declared as "public" - // in older compilers in order to use it... starting with VC7 we can declare it as "protected" -protected: -#endif - enum - { - STACKWALK_MAX_NAMELEN = 1024 - }; // max name length for found symbols - -protected: - // Entry for each Callstack-Entry - typedef struct CallstackEntry - { - DWORD64 offset; // if 0, we have no valid entry - CHAR name[STACKWALK_MAX_NAMELEN]; - CHAR undName[STACKWALK_MAX_NAMELEN]; - CHAR undFullName[STACKWALK_MAX_NAMELEN]; - DWORD64 offsetFromSmybol; - DWORD offsetFromLine; - DWORD lineNumber; - CHAR lineFileName[STACKWALK_MAX_NAMELEN]; - DWORD symType; - LPCSTR symTypeString; - CHAR moduleName[STACKWALK_MAX_NAMELEN]; - DWORD64 baseOfImage; - CHAR loadedImageName[STACKWALK_MAX_NAMELEN]; - } CallstackEntry; - - typedef enum CallstackEntryType - { - firstEntry, - nextEntry, - lastEntry - } CallstackEntryType; - - virtual void OnSymInit(LPCSTR szSearchPath, DWORD symOptions, LPCSTR szUserName); - virtual void OnLoadModule(LPCSTR img, - LPCSTR mod, - DWORD64 baseAddr, - DWORD size, - DWORD result, - LPCSTR symType, - LPCSTR pdbName, - ULONGLONG fileVersion); - virtual void OnCallstackEntry(CallstackEntryType eType, CallstackEntry& entry); - virtual void OnDbgHelpErr(LPCSTR szFuncName, DWORD gle, DWORD64 addr); - virtual void OnOutput(LPCSTR szText); - - StackWalkerInternal* m_sw; - HANDLE m_hProcess; - DWORD m_dwProcessId; - BOOL m_modulesLoaded; - LPSTR m_szSymPath; - - int m_options; - int m_MaxRecursionCount; - - static BOOL __stdcall myReadProcMem(HANDLE hProcess, - DWORD64 qwBaseAddress, - PVOID lpBuffer, - DWORD nSize, - LPDWORD lpNumberOfBytesRead); - - friend StackWalkerInternal; -}; // class StackWalker - -// The "ugly" assembler-implementation is needed for systems before XP -// If you have a new PSDK and you only compile for XP and later, then you can use -// the "RtlCaptureContext" -// Currently there is no define which determines the PSDK-Version... -// So we just use the compiler-version (and assumes that the PSDK is -// the one which was installed by the VS-IDE) - -// INFO: If you want, you can use the RtlCaptureContext if you only target XP and later... -// But I currently use it in x64/IA64 environments... -//#if defined(_M_IX86) && (_WIN32_WINNT <= 0x0500) && (_MSC_VER < 1400) - -#if defined(_M_IX86) -#ifdef CURRENT_THREAD_VIA_EXCEPTION -// TODO: The following is not a "good" implementation, -// because the callstack is only valid in the "__except" block... -#define GET_CURRENT_CONTEXT_STACKWALKER_CODEPLEX(c, contextFlags) \ - do \ - { \ - memset(&c, 0, sizeof(CONTEXT)); \ - EXCEPTION_POINTERS* pExp = NULL; \ - __try \ - { \ - throw 0; \ - } \ - __except (((pExp = GetExceptionInformation()) ? EXCEPTION_EXECUTE_HANDLER \ - : EXCEPTION_EXECUTE_HANDLER)) \ - { \ - } \ - if (pExp != NULL) \ - memcpy(&c, pExp->ContextRecord, sizeof(CONTEXT)); \ - c.ContextFlags = contextFlags; \ - } while (0); -#else -// clang-format off -// The following should be enough for walking the callstack... -#define GET_CURRENT_CONTEXT_STACKWALKER_CODEPLEX(c, contextFlags) \ - do \ - { \ - memset(&c, 0, sizeof(CONTEXT)); \ - c.ContextFlags = contextFlags; \ - __asm call x \ - __asm x: pop eax \ - __asm mov c.Eip, eax \ - __asm mov c.Ebp, ebp \ - __asm mov c.Esp, esp \ - } while (0) -// clang-format on -#endif - -#else - -// The following is defined for x86 (XP and higher), x64 and IA64: -#define GET_CURRENT_CONTEXT_STACKWALKER_CODEPLEX(c, contextFlags) \ - do \ - { \ - memset(&c, 0, sizeof(CONTEXT)); \ - c.ContextFlags = contextFlags; \ - RtlCaptureContext(&c); \ - } while (0); -#endif - -#endif //defined(_MSC_VER) - -#endif // __STACKWALKER_H__