From 4f133c6aa10cf998ee16b95b97bbed81263dd5f9 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sat, 25 Oct 2025 13:28:39 -0400 Subject: [PATCH 01/10] [build][ci] Update vcpkg baseline (#8300) --- .github/workflows/cmake.yml | 2 +- vcpkg.json | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/cmake.yml b/.github/workflows/cmake.yml index 154cd6c55b..82fdb8bc23 100644 --- a/.github/workflows/cmake.yml +++ b/.github/workflows/cmake.yml @@ -59,7 +59,7 @@ jobs: uses: lukka/run-vcpkg@v11.5 with: vcpkgDirectory: ${{ runner.workspace }}/vcpkg - vcpkgGitCommitId: 37c3e63a1306562f7f59c4c3c8892ddd50fdf992 # HEAD on 2024-02-24 + vcpkgGitCommitId: 74e6536215718009aae747d86d84b78376bf9e09 # HEAD on 2025-10-17 - name: configure run: cmake ${{ matrix.flags }} diff --git a/vcpkg.json b/vcpkg.json index ea1d2a9b5b..255ecd07c2 100644 --- a/vcpkg.json +++ b/vcpkg.json @@ -8,5 +8,5 @@ "protobuf", "libssh" ], - "builtin-baseline": "37c3e63a1306562f7f59c4c3c8892ddd50fdf992" + "builtin-baseline": "74e6536215718009aae747d86d84b78376bf9e09" } From 873e960e932a3c8bd41701755ad4716f2856b58c Mon Sep 17 00:00:00 2001 From: Ryan Blue Date: Sat, 25 Oct 2025 20:23:12 -0400 Subject: [PATCH 02/10] [ci] Update tools workflow for 2026 (#8301) --- .github/workflows/tools.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/tools.yml b/.github/workflows/tools.yml index f07960ba27..58e9ad449e 100644 --- a/.github/workflows/tools.yml +++ b/.github/workflows/tools.yml @@ -7,7 +7,7 @@ concurrency: cancel-in-progress: true env: - YEAR: 2025 + YEAR: 2026 jobs: build-artifacts: From a6a4912a80810e48c7d6a27589e6ce82c459ea03 Mon Sep 17 00:00:00 2001 From: Jason Daming Date: Mon, 27 Oct 2025 19:49:16 -0700 Subject: [PATCH 03/10] [snippets] Add ProfiledPIDController with feedforward snippets (#8280) Adds snippets demonstrating ProfiledPIDController usage with SimpleMotorFeedforward using the two-parameter calculate() method (currentVelocity, nextVelocity). These snippets will be used in frc-docs to document the recommended feedforward pattern with ProfiledPIDController. Co-authored-by: sciencewhiz --- .../ProfiledPIDFeedforward/cpp/Robot.cpp | 54 +++++++++++++++++++ .../src/main/cpp/snippets/snippets.json | 10 ++++ .../snippets/profiledpidfeedforward/Main.java | 25 +++++++++ .../profiledpidfeedforward/Robot.java | 51 ++++++++++++++++++ .../wpi/first/wpilibj/snippets/snippets.json | 11 ++++ 5 files changed, 151 insertions(+) create mode 100644 wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Main.java create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java diff --git a/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp new file mode 100644 index 0000000000..fc076263f6 --- /dev/null +++ b/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp @@ -0,0 +1,54 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/** + * ProfiledPIDController with feedforward snippets for frc-docs. + * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/controllers/profiled-pidcontroller.html + */ +class Robot : public frc::TimedRobot { + public: + Robot() { m_encoder.SetDistancePerPulse(1.0 / 256.0); } + + // Controls a simple motor's position using a SimpleMotorFeedforward + // and a ProfiledPIDController + void GoToPosition(units::meter_t goalPosition) { + auto pidVal = m_controller.Calculate( + units::meter_t{m_encoder.GetDistance()}, goalPosition); + m_motor.SetVoltage(units::volt_t{pidVal} + + m_feedforward.Calculate( + m_lastSpeed, m_controller.GetSetpoint().velocity)); + m_lastSpeed = m_controller.GetSetpoint().velocity; + } + + void TeleopPeriodic() override { + // Example usage: move to position 10.0 meters + GoToPosition(10.0_m); + } + + private: + frc::ProfiledPIDController m_controller{ + 1.0, 0.0, 0.0, {5_mps, 10_mps_sq}}; + frc::SimpleMotorFeedforward m_feedforward{0.5_V, 1.5_V / 1_mps, + 0.3_V / 1_mps_sq}; + frc::Encoder m_encoder{0, 1}; + frc::PWMSparkMax m_motor{0}; + + units::meters_per_second_t m_lastSpeed = 0_mps; +}; + +#ifndef RUNNING_FRC_TESTS +int main() { + return frc::StartRobot(); +} +#endif diff --git a/wpilibcExamples/src/main/cpp/snippets/snippets.json b/wpilibcExamples/src/main/cpp/snippets/snippets.json index db114169f0..4e2fca80a0 100644 --- a/wpilibcExamples/src/main/cpp/snippets/snippets.json +++ b/wpilibcExamples/src/main/cpp/snippets/snippets.json @@ -154,5 +154,15 @@ ], "foldername": "AccelerometerFilter", "gradlebase": "cpp" + }, + { + "name": "ProfiledPIDFeedforward", + "description": "Snippets of ProfiledPIDController with feedforward for frc-docs.", + "tags": [ + "PID", + "Profiled PID" + ], + "foldername": "ProfiledPIDFeedforward", + "gradlebase": "cpp" } ] diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Main.java new file mode 100644 index 0000000000..1fc6c2ec2b --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Main.java @@ -0,0 +1,25 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.wpilibj.snippets.profiledpidfeedforward; + +import edu.wpi.first.wpilibj.RobotBase; + +/** + * Do NOT add any static variables to this class, or any initialization at all. Unless you know what + * you are doing, do not modify this file except to change the parameter class to the startRobot + * call. + */ +public final class Main { + private Main() {} + + /** + * Main initialization function. Do not perform any initialization here. + * + *

If you change your main robot class, change the parameter type. + */ + public static void main(String... args) { + RobotBase.startRobot(Robot::new); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java new file mode 100644 index 0000000000..9f30e73e5f --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java @@ -0,0 +1,51 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.wpilibj.snippets.profiledpidfeedforward; + +import edu.wpi.first.math.controller.ProfiledPIDController; +import edu.wpi.first.math.controller.SimpleMotorFeedforward; +import edu.wpi.first.math.trajectory.TrapezoidProfile; +import edu.wpi.first.wpilibj.Encoder; +import edu.wpi.first.wpilibj.TimedRobot; +import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; + +/** + * ProfiledPIDController with feedforward snippets for frc-docs. + * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/controllers/profiled-pidcontroller.html + */ +public class Robot extends TimedRobot { + private final ProfiledPIDController m_controller = + new ProfiledPIDController(1.0, 0.0, 0.0, new TrapezoidProfile.Constraints(5.0, 10.0)); + private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(0.5, 1.5, 0.3); + private final Encoder m_encoder = new Encoder(0, 1); + private final PWMSparkMax m_motor = new PWMSparkMax(0); + + double m_lastSpeed; + + /** Called once at the beginning of the robot program. */ + public Robot() { + m_encoder.setDistancePerPulse(1.0 / 256.0); + } + + /** + * Controls a simple motor's position using a SimpleMotorFeedforward and a ProfiledPIDController. + * + * @param goalPosition the desired position + */ + public void goToPosition(double goalPosition) { + double pidVal = m_controller.calculate(m_encoder.getDistance(), goalPosition); + m_motor.setVoltage( + pidVal + + m_feedforward.calculateWithVelocities( + m_lastSpeed, m_controller.getSetpoint().velocity)); + m_lastSpeed = m_controller.getSetpoint().velocity; + } + + @Override + public void teleopPeriodic() { + // Example usage: move to position 10.0 + goToPosition(10.0); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json index f3f98a4752..bef8e76f4f 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json @@ -169,5 +169,16 @@ "foldername": "accelerometerfilter", "gradlebase": "java", "mainclass": "Main" + }, + { + "name": "ProfiledPIDFeedforward", + "description": "Snippets of ProfiledPIDController with feedforward for frc-docs.", + "tags": [ + "PID", + "Profiled PID" + ], + "foldername": "profiledpidfeedforward", + "gradlebase": "java", + "mainclass": "Robot" } ] From 4aef52a117cc99fb9790c29e4aba34420300936c Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 28 Oct 2025 20:17:04 -0700 Subject: [PATCH 04/10] [ci] Upgrade to wpiformat 2025.36 (#8308) clang-format 21 made some formatting changes. Since wpiformat's stdlib task was removed, I removed NOLINT comments for it and removed some std:: prefixes it added to comments. --- .github/workflows/lint-format.yml | 4 +- .../src/main/native/cpp/main.cpp | 2 +- .../halsim_gui/src/main/native/cpp/main.cpp | 2 +- .../src/main/native/include/HALDataSource.h | 16 +- .../src/main/native/cpp/main.cpp | 2 +- .../src/main/native/cpp/main.cpp | 2 +- .../halsim_xrp/src/main/native/cpp/main.cpp | 2 +- .../cpp/analysis/FeedforwardAnalysis.cpp | 10 +- upstream_utils/sleipnir.py | 5 +- .../native/include/frc2/command/CommandPtr.h | 3 +- wpimath/.styleguide | 3 +- .../main/native/include/frc/StateSpaceUtil.h | 2 +- .../native/include/frc/geometry/Ellipse2d.h | 4 +- .../main/native/include/frc/geometry/Pose3d.h | 8 +- .../native/include/frc/geometry/Quaternion.h | 4 +- .../native/thirdparty/sleipnir/.clang-format | 249 ------------------ .../native/thirdparty/sleipnir/.clang-tidy | 74 ------ .../native/thirdparty/sleipnir/.styleguide | 23 -- .../thirdparty/sleipnir/.styleguide-license | 1 - .../thirdparty/sleipnir/include/.styleguide | 14 - .../thirdparty/sleipnir/src/.styleguide | 13 - .../cpp/filter/LinearFilterOutputTest.cpp | 16 +- .../include/wpi/sendable/SendableHelper.h | 3 +- 23 files changed, 38 insertions(+), 424 deletions(-) delete mode 100644 wpimath/src/main/native/thirdparty/sleipnir/.clang-format delete mode 100644 wpimath/src/main/native/thirdparty/sleipnir/.clang-tidy delete mode 100644 wpimath/src/main/native/thirdparty/sleipnir/.styleguide delete mode 100644 wpimath/src/main/native/thirdparty/sleipnir/.styleguide-license delete mode 100644 wpimath/src/main/native/thirdparty/sleipnir/include/.styleguide delete mode 100644 wpimath/src/main/native/thirdparty/sleipnir/src/.styleguide diff --git a/.github/workflows/lint-format.yml b/.github/workflows/lint-format.yml index 7075ac11cb..05d6484f50 100644 --- a/.github/workflows/lint-format.yml +++ b/.github/workflows/lint-format.yml @@ -36,7 +36,7 @@ jobs: - name: Install wpiformat run: | python -m venv ${{ runner.temp }}/wpiformat - ${{ runner.temp }}/wpiformat/bin/pip3 install wpiformat==2025.34 + ${{ runner.temp }}/wpiformat/bin/pip3 install wpiformat==2025.36 - name: Run run: ${{ runner.temp }}/wpiformat/bin/wpiformat - name: Check output @@ -78,7 +78,7 @@ jobs: - name: Install wpiformat run: | python -m venv ${{ runner.temp }}/wpiformat - ${{ runner.temp }}/wpiformat/bin/pip3 install wpiformat==2025.34 + ${{ runner.temp }}/wpiformat/bin/pip3 install wpiformat==2025.36 - name: Create compile_commands.json run: | ./gradlew generateCompileCommands -Ptoolchain-optional-roboRio diff --git a/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp b/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp index 3686d3affd..f5e4cf3e44 100644 --- a/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp +++ b/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp @@ -186,7 +186,7 @@ extern "C" { #if defined(WIN32) || defined(_WIN32) __declspec(dllexport) #endif - int HALSIM_InitExtension(void) { +int HALSIM_InitExtension(void) { static bool once = false; if (once) { diff --git a/simulation/halsim_gui/src/main/native/cpp/main.cpp b/simulation/halsim_gui/src/main/native/cpp/main.cpp index 2df10c84f0..9fba6a555b 100644 --- a/simulation/halsim_gui/src/main/native/cpp/main.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/main.cpp @@ -45,7 +45,7 @@ extern "C" { #if defined(WIN32) || defined(_WIN32) __declspec(dllexport) #endif - int HALSIM_InitExtension(void) { +int HALSIM_InitExtension(void) { std::puts("Simulator GUI Initializing."); gui::CreateContext(); diff --git a/simulation/halsim_gui/src/main/native/include/HALDataSource.h b/simulation/halsim_gui/src/main/native/include/HALDataSource.h index 295b3f8ba5..c04f3589b3 100644 --- a/simulation/halsim_gui/src/main/native/include/HALDataSource.h +++ b/simulation/halsim_gui/src/main/native/include/HALDataSource.h @@ -57,13 +57,9 @@ HALSIM_Cancel##cbname##Callback(m_index, m_callback); \ } \ \ - int32_t GetIndex() const { \ - return m_index; \ - } \ + int32_t GetIndex() const { return m_index; } \ \ - int GetChannel() const { \ - return m_channel; \ - } \ + int GetChannel() const { return m_channel; } \ \ private: \ static void CallbackFunc(const char*, void* param, \ @@ -100,13 +96,9 @@ HALSIM_Cancel##cbname##Callback(m_index, m_channel, m_callback); \ } \ \ - int32_t GetIndex() const { \ - return m_index; \ - } \ + int32_t GetIndex() const { return m_index; } \ \ - int32_t GetChannel() const { \ - return m_channel; \ - } \ + int32_t GetChannel() const { return m_channel; } \ \ private: \ static void CallbackFunc(const char*, void* param, \ diff --git a/simulation/halsim_ws_client/src/main/native/cpp/main.cpp b/simulation/halsim_ws_client/src/main/native/cpp/main.cpp index 8e2e2fa569..f46fad6c04 100644 --- a/simulation/halsim_ws_client/src/main/native/cpp/main.cpp +++ b/simulation/halsim_ws_client/src/main/native/cpp/main.cpp @@ -18,7 +18,7 @@ extern "C" { __declspec(dllexport) #endif - int HALSIM_InitExtension(void) { +int HALSIM_InitExtension(void) { std::puts("HALSim WS Client Extension Initializing"); HAL_OnShutdown(nullptr, [](void*) { gClient.reset(); }); diff --git a/simulation/halsim_ws_server/src/main/native/cpp/main.cpp b/simulation/halsim_ws_server/src/main/native/cpp/main.cpp index 1ee0ae8bba..ef9f8a2081 100644 --- a/simulation/halsim_ws_server/src/main/native/cpp/main.cpp +++ b/simulation/halsim_ws_server/src/main/native/cpp/main.cpp @@ -18,7 +18,7 @@ extern "C" { #if defined(WIN32) || defined(_WIN32) __declspec(dllexport) #endif - int HALSIM_InitExtension(void) { +int HALSIM_InitExtension(void) { std::puts("Websocket WS Server Initializing."); HAL_OnShutdown(nullptr, [](void*) { gServer.reset(); }); diff --git a/simulation/halsim_xrp/src/main/native/cpp/main.cpp b/simulation/halsim_xrp/src/main/native/cpp/main.cpp index a399c592a0..4b338f4453 100644 --- a/simulation/halsim_xrp/src/main/native/cpp/main.cpp +++ b/simulation/halsim_xrp/src/main/native/cpp/main.cpp @@ -25,7 +25,7 @@ extern "C" { __declspec(dllexport) #endif - int HALSIM_InitExtension(void) { +int HALSIM_InitExtension(void) { std::puts("HALSim XRP Extension Initializing"); HAL_OnShutdown(nullptr, [](void*) { gClient.reset(); }); diff --git a/sysid/src/main/native/cpp/analysis/FeedforwardAnalysis.cpp b/sysid/src/main/native/cpp/analysis/FeedforwardAnalysis.cpp index 3f517d9da2..e0ece513ed 100644 --- a/sysid/src/main/native/cpp/analysis/FeedforwardAnalysis.cpp +++ b/sysid/src/main/native/cpp/analysis/FeedforwardAnalysis.cpp @@ -251,17 +251,17 @@ OLSResult CalculateFeedforwardGains(const Storage& data, if (type == analysis::kArm) { // dx/dt = -Kv/Ka x + 1/Ka u - Ks/Ka sgn(x) - // - Kg/Ka cos(offset) cos(angle) NOLINT - // + Kg/Ka sin(offset) sin(angle) NOLINT - // dx/dt = αx + βu + γ sgn(x) + δ cos(angle) + ε sin(angle) NOLINT + // - Kg/Ka cos(offset) cos(angle) + // + Kg/Ka sin(offset) sin(angle) + // dx/dt = αx + βu + γ sgn(x) + δ cos(angle) + ε sin(angle) // δ = -Kg/Ka cos(offset) // ε = Kg/Ka sin(offset) double δ = ols.coeffs[3]; double ε = ols.coeffs[4]; - // Kg = hypot(δ, ε)/β NOLINT - // offset = atan2(ε, -δ) NOLINT + // Kg = hypot(δ, ε)/β + // offset = atan2(ε, -δ) gains.emplace_back(std::hypot(δ, ε) / β); gains.emplace_back(std::atan2(ε, -δ)); } diff --git a/upstream_utils/sleipnir.py b/upstream_utils/sleipnir.py index 8600d0be13..a83520464b 100755 --- a/upstream_utils/sleipnir.py +++ b/upstream_utils/sleipnir.py @@ -19,10 +19,7 @@ def copy_upstream_src(wpilib_root: Path): # Copy Sleipnir files into allwpilib walk_cwd_and_copy_if( lambda dp, f: (has_prefix(dp, Path("include")) or has_prefix(dp, Path("src"))) - or f == ".clang-format" - or f == ".clang-tidy" - or f == ".styleguide" - or f == ".styleguide-license", + and f not in [".styleguide", ".styleguide-license"], wpimath / "src/main/native/thirdparty/sleipnir", ) diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h b/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h index fb54d3bc09..e7c284e6e4 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h @@ -25,8 +25,7 @@ namespace frc2 { * std::unique_ptr, use CommandPtr::Unwrap to convert. * CommandPtr::UnwrapVector does the same for vectors. */ -class [[nodiscard]] -CommandPtr final { +class [[nodiscard]] CommandPtr final { public: explicit CommandPtr(std::unique_ptr&& command); diff --git a/wpimath/.styleguide b/wpimath/.styleguide index 91d68ae2b2..5ce1237835 100644 --- a/wpimath/.styleguide +++ b/wpimath/.styleguide @@ -19,8 +19,6 @@ generatedFileExclude { src/main/native/include/unsupported/ src/main/native/thirdparty/ src/test/native/cpp/UnitsTest\.cpp$ - src/test/native/cpp/drake/ - src/test/native/include/drake/ src/generated/main/java/edu/wpi/first/math/proto src/generated/main/native/cpp } @@ -41,6 +39,7 @@ includeOtherLibs { ^gcem/ ^google/ ^gtest/ + ^sleipnir/ ^unsupported/ ^wpi/ } diff --git a/wpimath/src/main/native/include/frc/StateSpaceUtil.h b/wpimath/src/main/native/include/frc/StateSpaceUtil.h index 6c58485d45..b04aea48ce 100644 --- a/wpimath/src/main/native/include/frc/StateSpaceUtil.h +++ b/wpimath/src/main/native/include/frc/StateSpaceUtil.h @@ -260,7 +260,7 @@ WPILIB_DLLEXPORT constexpr Eigen::Vector3d PoseTo3dVector(const Pose2d& pose) { } /** - * Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)]. + * Converts a Pose2d into a vector of [x, y, cos(theta), sin(theta)]. * * @param pose The pose that is being represented. * diff --git a/wpimath/src/main/native/include/frc/geometry/Ellipse2d.h b/wpimath/src/main/native/include/frc/geometry/Ellipse2d.h index 629faf5922..1c3a8382af 100644 --- a/wpimath/src/main/native/include/frc/geometry/Ellipse2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Ellipse2d.h @@ -91,7 +91,7 @@ class WPILIB_DLLEXPORT Ellipse2d { auto a = units::math::max(m_xSemiAxis, m_ySemiAxis); // Minor semi-axis - auto b = units::math::min(m_xSemiAxis, m_ySemiAxis); // NOLINT + auto b = units::math::min(m_xSemiAxis, m_ySemiAxis); auto c = units::math::sqrt(a * a - b * b); @@ -203,7 +203,9 @@ class WPILIB_DLLEXPORT Ellipse2d { auto x = rotPoint.X() - m_center.X(); auto y = rotPoint.Y() - m_center.Y(); + // NOLINTNEXTLINE (bugprone-integer-division) return (x * x) / (m_xSemiAxis * m_xSemiAxis) + + // NOLINTNEXTLINE (bugprone-integer-division) (y * y) / (m_ySemiAxis * m_ySemiAxis); } }; diff --git a/wpimath/src/main/native/include/frc/geometry/Pose3d.h b/wpimath/src/main/native/include/frc/geometry/Pose3d.h index e2ec7c4609..17aac42648 100644 --- a/wpimath/src/main/native/include/frc/geometry/Pose3d.h +++ b/wpimath/src/main/native/include/frc/geometry/Pose3d.h @@ -432,8 +432,8 @@ constexpr Pose3d Pose3d::Exp(const Twist3d& twist) const { B = 1 / 2.0 - thetaSq / 24 + thetaSq * thetaSq / 720; C = 1 / 6.0 - thetaSq / 120 + thetaSq * thetaSq / 5040; } else { - // A = std::sin(θ)/θ - // B = (1 - std::cos(θ)) / θ² + // A = sin(θ)/θ + // B = (1 - cos(θ)) / θ² // C = (1 - A) / θ² A = gcem::sin(theta) / theta; B = (1 - gcem::cos(theta)) / thetaSq; @@ -491,8 +491,8 @@ constexpr Twist3d Pose3d::Log(const Pose3d& end) const { // https://www.wolframalpha.com/input?i2d=true&i=series+expansion+of+Divide%5B1-Divide%5BDivide%5Bsin%5C%2840%29x%5C%2841%29%2Cx%5D%2C2Divide%5B1-cos%5C%2840%29x%5C%2841%29%2CPower%5Bx%2C2%5D%5D%5D%2CPower%5Bx%2C2%5D%5D+at+x%3D0 C = 1 / 12.0 + thetaSq / 720 + thetaSq * thetaSq / 30240; } else { - // A = std::sin(θ)/θ - // B = (1 - std::cos(θ)) / θ² + // A = sin(θ)/θ + // B = (1 - cos(θ)) / θ² // C = (1 - A/(2*B)) / θ² double A = gcem::sin(theta) / theta; double B = (1 - gcem::cos(theta)) / thetaSq; diff --git a/wpimath/src/main/native/include/frc/geometry/Quaternion.h b/wpimath/src/main/native/include/frc/geometry/Quaternion.h index 65c6a8265e..09d21e38f2 100644 --- a/wpimath/src/main/native/include/frc/geometry/Quaternion.h +++ b/wpimath/src/main/native/include/frc/geometry/Quaternion.h @@ -296,8 +296,8 @@ class WPILIB_DLLEXPORT Quaternion { // 𝑣⃗ = θ * v̂ // v̂ = 𝑣⃗ / θ - // 𝑞 = std::cos(θ/2) + std::sin(θ/2) * v̂ - // 𝑞 = std::cos(θ/2) + std::sin(θ/2) / θ * 𝑣⃗ + // 𝑞 = cos(θ/2) + sin(θ/2) * v̂ + // 𝑞 = cos(θ/2) + sin(θ/2) / θ * 𝑣⃗ double theta = gcem::hypot(rvec(0), rvec(1), rvec(2)); double cos = gcem::cos(theta / 2); diff --git a/wpimath/src/main/native/thirdparty/sleipnir/.clang-format b/wpimath/src/main/native/thirdparty/sleipnir/.clang-format deleted file mode 100644 index 5e5e1773c3..0000000000 --- a/wpimath/src/main/native/thirdparty/sleipnir/.clang-format +++ /dev/null @@ -1,249 +0,0 @@ ---- -Language: Cpp -BasedOnStyle: Google -AccessModifierOffset: -1 -AlignAfterOpenBracket: Align -AlignArrayOfStructures: None -AlignConsecutiveAssignments: - Enabled: false - AcrossEmptyLines: false - AcrossComments: false - AlignCompound: false - PadOperators: true -AlignConsecutiveBitFields: - Enabled: false - AcrossEmptyLines: false - AcrossComments: false - AlignCompound: false - PadOperators: false -AlignConsecutiveDeclarations: - Enabled: false - AcrossEmptyLines: false - AcrossComments: false - AlignCompound: false - PadOperators: false -AlignConsecutiveMacros: - Enabled: false - AcrossEmptyLines: false - AcrossComments: false - AlignCompound: false - PadOperators: false -AlignConsecutiveShortCaseStatements: - Enabled: false - AcrossEmptyLines: false - AcrossComments: false - AlignCaseColons: false -AlignEscapedNewlines: Left -AlignOperands: Align -AlignTrailingComments: - Kind: Always - OverEmptyLines: 0 -AllowAllArgumentsOnNextLine: true -AllowAllParametersOfDeclarationOnNextLine: true -AllowShortBlocksOnASingleLine: Never -AllowShortCaseLabelsOnASingleLine: false -AllowShortEnumsOnASingleLine: true -AllowShortFunctionsOnASingleLine: Inline -AllowShortIfStatementsOnASingleLine: Never -AllowShortLambdasOnASingleLine: All -AllowShortLoopsOnASingleLine: false -AlwaysBreakAfterDefinitionReturnType: None -AlwaysBreakAfterReturnType: None -AlwaysBreakBeforeMultilineStrings: true -AlwaysBreakTemplateDeclarations: Yes -BinPackArguments: true -BinPackParameters: true -BitFieldColonSpacing: Both -BraceWrapping: - AfterCaseLabel: false - AfterClass: false - AfterControlStatement: Never - AfterEnum: false - AfterExternBlock: false - AfterFunction: false - AfterNamespace: false - AfterObjCDeclaration: false - AfterStruct: false - AfterUnion: false - BeforeCatch: false - BeforeElse: false - BeforeLambdaBody: false - BeforeWhile: false - IndentBraces: false - SplitEmptyFunction: true - SplitEmptyRecord: true - SplitEmptyNamespace: true -BreakAfterAttributes: Always -BreakAfterJavaFieldAnnotations: false -BreakArrays: true -BreakBeforeBinaryOperators: None -BreakBeforeConceptDeclarations: Always -BreakBeforeBraces: Attach -BreakBeforeInlineASMColon: OnlyMultiline -BreakBeforeTernaryOperators: true -BreakConstructorInitializers: BeforeColon -BreakInheritanceList: BeforeColon -BreakStringLiterals: true -ColumnLimit: 80 -CommentPragmas: '^ IWYU pragma:' -CompactNamespaces: false -ConstructorInitializerIndentWidth: 4 -ContinuationIndentWidth: 4 -Cpp11BracedListStyle: true -DerivePointerAlignment: false -DisableFormat: false -EmptyLineAfterAccessModifier: Never -EmptyLineBeforeAccessModifier: LogicalBlock -ExperimentalAutoDetectBinPacking: false -FixNamespaceComments: true -IncludeBlocks: Regroup -IncludeCategories: - - Regex: '^' - Priority: 2 - SortPriority: 0 - CaseSensitive: false - - Regex: '^<.*\.h>' - Priority: 1 - SortPriority: 0 - CaseSensitive: false - - Regex: '^<.*' - Priority: 2 - SortPriority: 0 - CaseSensitive: false - - Regex: '.*' - Priority: 3 - SortPriority: 0 - CaseSensitive: false -IncludeIsMainRegex: '([-_](test|unittest))?$' -IncludeIsMainSourceRegex: '' -IndentAccessModifiers: false -IndentCaseBlocks: false -IndentCaseLabels: true -IndentExternBlock: AfterExternBlock -IndentGotoLabels: true -IndentPPDirectives: None -IndentRequiresClause: true -IndentWidth: 2 -IndentWrappedFunctionNames: false -InsertBraces: false -InsertNewlineAtEOF: false -InsertTrailingCommas: None -IntegerLiteralSeparator: - Binary: 0 - BinaryMinDigits: 0 - Decimal: 0 - DecimalMinDigits: 0 - Hex: 0 - HexMinDigits: 0 -JavaScriptQuotes: Leave -JavaScriptWrapImports: true -KeepEmptyLinesAtTheStartOfBlocks: false -KeepEmptyLinesAtEOF: false -LambdaBodyIndentation: Signature -LineEnding: DeriveLF -MacroBlockBegin: '' -MacroBlockEnd: '' -MaxEmptyLinesToKeep: 1 -NamespaceIndentation: None -ObjCBinPackProtocolList: Never -ObjCBlockIndentWidth: 2 -ObjCBreakBeforeNestedBlockParam: true -ObjCSpaceAfterProperty: false -ObjCSpaceBeforeProtocolList: true -PackConstructorInitializers: NextLine -PenaltyBreakAssignment: 2 -PenaltyBreakBeforeFirstCallParameter: 1 -PenaltyBreakComment: 300 -PenaltyBreakFirstLessLess: 120 -PenaltyBreakOpenParenthesis: 0 -PenaltyBreakString: 1000 -PenaltyBreakTemplateDeclaration: 10 -PenaltyExcessCharacter: 1000000 -PenaltyIndentedWhitespace: 0 -PenaltyReturnTypeOnItsOwnLine: 200 -PointerAlignment: Left -PPIndentWidth: -1 -QualifierAlignment: Leave -RawStringFormats: - - Language: Cpp - Delimiters: - - cc - - CC - - cpp - - Cpp - - CPP - - 'c++' - - 'C++' - CanonicalDelimiter: '' - BasedOnStyle: google - - Language: TextProto - Delimiters: - - pb - - PB - - proto - - PROTO - EnclosingFunctions: - - EqualsProto - - EquivToProto - - PARSE_PARTIAL_TEXT_PROTO - - PARSE_TEST_PROTO - - PARSE_TEXT_PROTO - - ParseTextOrDie - - ParseTextProtoOrDie - - ParseTestProto - - ParsePartialTestProto - CanonicalDelimiter: pb - BasedOnStyle: google -ReferenceAlignment: Pointer -ReflowComments: true -RemoveBracesLLVM: false -RemoveParentheses: Leave -RemoveSemicolon: false -RequiresClausePosition: OwnLine -RequiresExpressionIndentation: OuterScope -SeparateDefinitionBlocks: Leave -ShortNamespaceLines: 1 -SortIncludes: false -SortJavaStaticImport: Before -SortUsingDeclarations: LexicographicNumeric -SpaceAfterCStyleCast: false -SpaceAfterLogicalNot: false -SpaceAfterTemplateKeyword: true -SpaceAroundPointerQualifiers: Default -SpaceBeforeAssignmentOperators: true -SpaceBeforeCaseColon: false -SpaceBeforeCpp11BracedList: false -SpaceBeforeCtorInitializerColon: true -SpaceBeforeInheritanceColon: true -SpaceBeforeJsonColon: false -SpaceBeforeParens: ControlStatements -SpaceBeforeParensOptions: - AfterControlStatements: true - AfterForeachMacros: true - AfterFunctionDefinitionName: false - AfterFunctionDeclarationName: false - AfterIfMacros: true - AfterOverloadedOperator: false - AfterRequiresInClause: false - AfterRequiresInExpression: false - BeforeNonEmptyParentheses: false -SpaceBeforeRangeBasedForLoopColon: true -SpaceBeforeSquareBrackets: false -SpaceInEmptyBlock: false -SpacesBeforeTrailingComments: 2 -SpacesInAngles: Never -SpacesInContainerLiterals: true -SpacesInLineCommentPrefix: - Minimum: 1 - Maximum: -1 -SpacesInParens: Never -SpacesInParensOptions: - InCStyleCasts: false - InConditionalStatements: false - InEmptyParentheses: false - Other: false -SpacesInSquareBrackets: false -Standard: c++20 -TabWidth: 8 -UseTab: Never -... diff --git a/wpimath/src/main/native/thirdparty/sleipnir/.clang-tidy b/wpimath/src/main/native/thirdparty/sleipnir/.clang-tidy deleted file mode 100644 index cfb2b12f2a..0000000000 --- a/wpimath/src/main/native/thirdparty/sleipnir/.clang-tidy +++ /dev/null @@ -1,74 +0,0 @@ -Checks: - 'bugprone-assert-side-effect, - bugprone-bool-pointer-implicit-conversion, - bugprone-copy-constructor-init, - bugprone-dangling-handle, - bugprone-dynamic-static-initializers, - bugprone-forward-declaration-namespace, - bugprone-forwarding-reference-overload, - bugprone-inaccurate-erase, - bugprone-incorrect-roundings, - bugprone-integer-division, - bugprone-lambda-function-name, - bugprone-misplaced-operator-in-strlen-in-alloc, - bugprone-misplaced-widening-cast, - bugprone-move-forwarding-reference, - bugprone-multiple-statement-macro, - bugprone-parent-virtual-call, - bugprone-posix-return, - bugprone-sizeof-container, - bugprone-sizeof-expression, - bugprone-spuriously-wake-up-functions, - bugprone-string-constructor, - bugprone-string-integer-assignment, - bugprone-string-literal-with-embedded-nul, - bugprone-suspicious-enum-usage, - bugprone-suspicious-include, - bugprone-suspicious-memset-usage, - bugprone-suspicious-missing-comma, - bugprone-suspicious-semicolon, - bugprone-suspicious-string-compare, - bugprone-throw-keyword-missing, - bugprone-too-small-loop-variable, - bugprone-undefined-memory-manipulation, - bugprone-undelegated-constructor, - bugprone-unhandled-self-assignment, - bugprone-unused-raii, - bugprone-virtual-near-miss, - cert-err52-cpp, - cert-err60-cpp, - cert-mem57-cpp, - cert-oop57-cpp, - cert-oop58-cpp, - clang-diagnostic-*, - -clang-diagnostic-deprecated-declarations, - -clang-diagnostic-#warnings, - -clang-diagnostic-pedantic, - clang-analyzer-*, - -clang-analyzer-core.uninitialized.UndefReturn, - -clang-analyzer-optin.cplusplus.UninitializedObject, - -clang-analyzer-optin.portability.UnixAPI, - -clang-analyzer-unix.Malloc, - -cppcoreguidelines-slicing, - google-build-namespaces, - google-explicit-constructor, - google-global-names-in-headers, - google-readability-avoid-underscore-in-googletest-name, - google-readability-casting, - google-runtime-operator, - misc-definitions-in-headers, - misc-misplaced-const, - misc-new-delete-overloads, - misc-non-copyable-objects, - modernize-avoid-bind, - modernize-concat-nested-namespaces, - modernize-make-shared, - modernize-make-unique, - modernize-pass-by-value, - modernize-use-default-member-init, - modernize-use-noexcept, - modernize-use-nullptr, - modernize-use-override, - modernize-use-using, - readability-braces-around-statements' -FormatStyle: file diff --git a/wpimath/src/main/native/thirdparty/sleipnir/.styleguide b/wpimath/src/main/native/thirdparty/sleipnir/.styleguide deleted file mode 100644 index 054f5eb80e..0000000000 --- a/wpimath/src/main/native/thirdparty/sleipnir/.styleguide +++ /dev/null @@ -1,23 +0,0 @@ -cppHeaderFileInclude { - \.hpp$ -} - -cppSrcFileInclude { - \.cpp$ -} - -modifiableFileExclude { - \.patch$ - \.png$ - \.svg$ - jormungandr/cpp/docstrings\.hpp$ - jormungandr/py\.typed$ -} - -includeOtherLibs { - ^Eigen/ - ^catch2/ - ^gch/ - ^nanobind/ - ^sleipnir/ -} diff --git a/wpimath/src/main/native/thirdparty/sleipnir/.styleguide-license b/wpimath/src/main/native/thirdparty/sleipnir/.styleguide-license deleted file mode 100644 index d664772a55..0000000000 --- a/wpimath/src/main/native/thirdparty/sleipnir/.styleguide-license +++ /dev/null @@ -1 +0,0 @@ -// Copyright (c) Sleipnir contributors diff --git a/wpimath/src/main/native/thirdparty/sleipnir/include/.styleguide b/wpimath/src/main/native/thirdparty/sleipnir/include/.styleguide deleted file mode 100644 index 03938557c2..0000000000 --- a/wpimath/src/main/native/thirdparty/sleipnir/include/.styleguide +++ /dev/null @@ -1,14 +0,0 @@ -cppHeaderFileInclude { - \.hpp$ -} - -cppSrcFileInclude { - \.cpp$ -} - -includeOtherLibs { - ^Eigen/ - ^fmt/ - ^gch/ - ^wpi/ -} diff --git a/wpimath/src/main/native/thirdparty/sleipnir/src/.styleguide b/wpimath/src/main/native/thirdparty/sleipnir/src/.styleguide deleted file mode 100644 index 4f4c762040..0000000000 --- a/wpimath/src/main/native/thirdparty/sleipnir/src/.styleguide +++ /dev/null @@ -1,13 +0,0 @@ -cppHeaderFileInclude { - \.hpp$ -} - -cppSrcFileInclude { - \.cpp$ -} - -includeOtherLibs { - ^Eigen/ - ^fmt/ - ^gch/ -} diff --git a/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp b/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp index 919552534d..c69e3f8f50 100644 --- a/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp +++ b/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp @@ -192,11 +192,11 @@ TEST(LinearFilterOutputTest, CentralFiniteDifference) { AssertCentralResults<1, 3>( [](double x) { - // f(x) = std::sin(x) + // f(x) = sin(x) return std::sin(x); }, [](double x) { - // df/dx = std::cos(x) + // df/dx = cos(x) return std::cos(x); }, h, -20.0, 20.0); @@ -225,11 +225,11 @@ TEST(LinearFilterOutputTest, CentralFiniteDifference) { AssertCentralResults<2, 5>( [](double x) { - // f(x) = std::sin(x) + // f(x) = sin(x) return std::sin(x); }, [](double x) { - // d²f/dx² = -std::sin(x) + // d²f/dx² = -sin(x) return -std::sin(x); }, h, -20.0, 20.0); @@ -265,11 +265,11 @@ TEST(LinearFilterOutputTest, BackwardFiniteDifference) { AssertBackwardResults<1, 2>( [](double x) { - // f(x) = std::sin(x) + // f(x) = sin(x) return std::sin(x); }, [](double x) { - // df/dx = std::cos(x) + // df/dx = cos(x) return std::cos(x); }, h, -20.0, 20.0); @@ -298,11 +298,11 @@ TEST(LinearFilterOutputTest, BackwardFiniteDifference) { AssertBackwardResults<2, 4>( [](double x) { - // f(x) = std::sin(x) + // f(x) = sin(x) return std::sin(x); }, [](double x) { - // d²f/dx² = -std::sin(x) + // d²f/dx² = -sin(x) return -std::sin(x); }, h, -20.0, 20.0); diff --git a/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h b/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h index 739a95ee08..8b3f4b1b21 100644 --- a/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h +++ b/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h @@ -39,8 +39,7 @@ class SendableHelper { // See https://bugzilla.mozilla.org/show_bug.cgi?id=1442819 __attribute__((no_sanitize("vptr"))) #endif - constexpr SendableHelper& - operator=(SendableHelper&& rhs) { + constexpr SendableHelper& operator=(SendableHelper&& rhs) { if (!std::is_constant_evaluated()) { // it is safe to call Move() multiple times with the same rhs SendableRegistry::Move(static_cast(this), From 58ba536351607bdc34e3559b5bb7c0a52b5d1981 Mon Sep 17 00:00:00 2001 From: Thad House Date: Tue, 28 Oct 2025 20:18:02 -0700 Subject: [PATCH 05/10] [wpilib] Remove Jaguar (and other) motor controllers (#8298) https://community.firstinspires.org/2025-robot-rules-preview-for-2026 --- styleguide/spotbugs-exclude.xml | 4 - .../main/native/cpp/motorcontrol/DMC60.cpp | 20 --- .../main/native/cpp/motorcontrol/Jaguar.cpp | 20 --- .../main/native/cpp/motorcontrol/SD540.cpp | 20 --- .../main/native/cpp/motorcontrol/Victor.cpp | 20 --- .../native/include/frc/motorcontrol/DMC60.h | 43 ------ .../native/include/frc/motorcontrol/Jaguar.h | 43 ------ .../native/include/frc/motorcontrol/SD540.h | 43 ------ .../native/include/frc/motorcontrol/Victor.h | 43 ------ .../cpp/motorcontrol/NidecBrushless.cpp | 86 ----------- .../include/frc/motorcontrol/NidecBrushless.h | 103 ------------- .../include/frc/shuffleboard/BuiltInWidgets.h | 4 - .../src/main/native/cpp/CounterTest.cpp | 6 +- .../src/main/native/cpp/DMATest.cpp | 4 +- .../src/main/native/cpp/MotorEncoderTest.cpp | 6 +- .../main/native/cpp/MotorInvertingTest.cpp | 6 +- .../src/generate/pwm_motor_controllers.json | 53 ------- .../wpi/first/wpilibj/motorcontrol/DMC60.java | 48 ------ .../first/wpilibj/motorcontrol/Jaguar.java | 48 ------ .../wpi/first/wpilibj/motorcontrol/SD540.java | 48 ------ .../first/wpilibj/motorcontrol/Victor.java | 48 ------ .../wpilibj/motorcontrol/NidecBrushless.java | 145 ------------------ .../wpilibj/shuffleboard/BuiltInWidgets.java | 4 - .../java/edu/wpi/first/wpilibj/DMATest.java | 4 +- .../edu/wpi/first/wpilibj/test/TestBench.java | 22 ++- 25 files changed, 20 insertions(+), 871 deletions(-) delete mode 100644 wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp delete mode 100644 wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp delete mode 100644 wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp delete mode 100644 wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp delete mode 100644 wpilibc/src/generated/main/native/include/frc/motorcontrol/DMC60.h delete mode 100644 wpilibc/src/generated/main/native/include/frc/motorcontrol/Jaguar.h delete mode 100644 wpilibc/src/generated/main/native/include/frc/motorcontrol/SD540.h delete mode 100644 wpilibc/src/generated/main/native/include/frc/motorcontrol/Victor.h delete mode 100644 wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp delete mode 100644 wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h delete mode 100644 wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java delete mode 100644 wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java delete mode 100644 wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java delete mode 100644 wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java delete mode 100644 wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java diff --git a/styleguide/spotbugs-exclude.xml b/styleguide/spotbugs-exclude.xml index 084206b4e0..f3fbffb591 100644 --- a/styleguide/spotbugs-exclude.xml +++ b/styleguide/spotbugs-exclude.xml @@ -32,10 +32,6 @@ - - - - diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp deleted file mode 100644 index 72eac176fd..0000000000 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp +++ /dev/null @@ -1,20 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY - -#include "frc/motorcontrol/DMC60.h" - -#include - -using namespace frc; - -DMC60::DMC60(int channel) : PWMMotorController("DMC60", channel) { - m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); - m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); - m_pwm.SetSpeed(0.0); - m_pwm.SetZeroLatch(); - - HAL_Report(HALUsageReporting::kResourceType_DigilentDMC60, GetChannel() + 1); -} diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp deleted file mode 100644 index 348ff568df..0000000000 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp +++ /dev/null @@ -1,20 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY - -#include "frc/motorcontrol/Jaguar.h" - -#include - -using namespace frc; - -Jaguar::Jaguar(int channel) : PWMMotorController("Jaguar", channel) { - m_pwm.SetBounds(2.31_ms, 1.55_ms, 1.507_ms, 1.454_ms, 0.697_ms); - m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); - m_pwm.SetSpeed(0.0); - m_pwm.SetZeroLatch(); - - HAL_Report(HALUsageReporting::kResourceType_Jaguar, GetChannel() + 1); -} diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp deleted file mode 100644 index c39e77f63f..0000000000 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp +++ /dev/null @@ -1,20 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY - -#include "frc/motorcontrol/SD540.h" - -#include - -using namespace frc; - -SD540::SD540(int channel) : PWMMotorController("SD540", channel) { - m_pwm.SetBounds(2.05_ms, 1.55_ms, 1.5_ms, 1.44_ms, 0.94_ms); - m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); - m_pwm.SetSpeed(0.0); - m_pwm.SetZeroLatch(); - - HAL_Report(HALUsageReporting::kResourceType_MindsensorsSD540, GetChannel() + 1); -} diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp deleted file mode 100644 index 7062518bef..0000000000 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp +++ /dev/null @@ -1,20 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY - -#include "frc/motorcontrol/Victor.h" - -#include - -using namespace frc; - -Victor::Victor(int channel) : PWMMotorController("Victor", channel) { - m_pwm.SetBounds(2.027_ms, 1.525_ms, 1.507_ms, 1.49_ms, 1.026_ms); - m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_2X); - m_pwm.SetSpeed(0.0); - m_pwm.SetZeroLatch(); - - HAL_Report(HALUsageReporting::kResourceType_Victor, GetChannel() + 1); -} diff --git a/wpilibc/src/generated/main/native/include/frc/motorcontrol/DMC60.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/DMC60.h deleted file mode 100644 index e994dc86d2..0000000000 --- a/wpilibc/src/generated/main/native/include/frc/motorcontrol/DMC60.h +++ /dev/null @@ -1,43 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY - -#pragma once - -#include "frc/motorcontrol/PWMMotorController.h" - -namespace frc { - -/** - * Digilent DMC 60 Motor Controller with PWM control. - * - * Note that the DMC 60 uses the following bounds for PWM values. These - * values should work reasonably well for most controllers, but if users - * experience issues such as asymmetric behavior around the deadband or - * inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the DMC 60 User - * Manual available from Digilent. - * - * \li 2.004ms = full "forward" - * \li 1.520ms = the "high end" of the deadband range - * \li 1.500ms = center of the deadband range (off) - * \li 1.480ms = the "low end" of the deadband range - * \li 0.997ms = full "reverse" - */ -class DMC60 : public PWMMotorController { - public: - /** - * Constructor for a DMC 60 connected via PWM. - * - * @param channel The PWM channel that the DMC 60 is attached to. 0-9 are - * on-board, 10-19 are on the MXP port - */ - explicit DMC60(int channel); - - DMC60(DMC60&&) = default; - DMC60& operator=(DMC60&&) = default; -}; - -} // namespace frc diff --git a/wpilibc/src/generated/main/native/include/frc/motorcontrol/Jaguar.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/Jaguar.h deleted file mode 100644 index 513b4c43ef..0000000000 --- a/wpilibc/src/generated/main/native/include/frc/motorcontrol/Jaguar.h +++ /dev/null @@ -1,43 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY - -#pragma once - -#include "frc/motorcontrol/PWMMotorController.h" - -namespace frc { - -/** - * Luminary Micro / Vex Robotics Jaguar Motor Controller with PWM control. - * - * Note that the Jaguar uses the following bounds for PWM values. These - * values should work reasonably well for most controllers, but if users - * experience issues such as asymmetric behavior around the deadband or - * inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the Jaguar User - * Manual available from Luminary Micro / Vex Robotics. - * - * \li 2.310ms = full "forward" - * \li 1.550ms = the "high end" of the deadband range - * \li 1.507ms = center of the deadband range (off) - * \li 1.454ms = the "low end" of the deadband range - * \li 0.697ms = full "reverse" - */ -class Jaguar : public PWMMotorController { - public: - /** - * Constructor for a Jaguar connected via PWM. - * - * @param channel The PWM channel that the Jaguar is attached to. 0-9 are - * on-board, 10-19 are on the MXP port - */ - explicit Jaguar(int channel); - - Jaguar(Jaguar&&) = default; - Jaguar& operator=(Jaguar&&) = default; -}; - -} // namespace frc diff --git a/wpilibc/src/generated/main/native/include/frc/motorcontrol/SD540.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/SD540.h deleted file mode 100644 index 5cbc4f9584..0000000000 --- a/wpilibc/src/generated/main/native/include/frc/motorcontrol/SD540.h +++ /dev/null @@ -1,43 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY - -#pragma once - -#include "frc/motorcontrol/PWMMotorController.h" - -namespace frc { - -/** - * Mindsensors SD540 Motor Controller with PWM control. - * - * Note that the SD540 uses the following bounds for PWM values. These - * values should work reasonably well for most controllers, but if users - * experience issues such as asymmetric behavior around the deadband or - * inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the SD540 User - * Manual available from Mindsensors. - * - * \li 2.050ms = full "forward" - * \li 1.550ms = the "high end" of the deadband range - * \li 1.500ms = center of the deadband range (off) - * \li 1.440ms = the "low end" of the deadband range - * \li 0.940ms = full "reverse" - */ -class SD540 : public PWMMotorController { - public: - /** - * Constructor for a SD540 connected via PWM. - * - * @param channel The PWM channel that the SD540 is attached to. 0-9 are - * on-board, 10-19 are on the MXP port - */ - explicit SD540(int channel); - - SD540(SD540&&) = default; - SD540& operator=(SD540&&) = default; -}; - -} // namespace frc diff --git a/wpilibc/src/generated/main/native/include/frc/motorcontrol/Victor.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/Victor.h deleted file mode 100644 index 95d6ed0fc3..0000000000 --- a/wpilibc/src/generated/main/native/include/frc/motorcontrol/Victor.h +++ /dev/null @@ -1,43 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY - -#pragma once - -#include "frc/motorcontrol/PWMMotorController.h" - -namespace frc { - -/** - * Vex Robotics Victor 888 Motor Controller with PWM control. - * - * Note that the Victor 888 uses the following bounds for PWM values. These - * values should work reasonably well for most controllers, but if users - * experience issues such as asymmetric behavior around the deadband or - * inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the Victor 888 User - * Manual available from Vex Robotics. - * - * \li 2.027ms = full "forward" - * \li 1.525ms = the "high end" of the deadband range - * \li 1.507ms = center of the deadband range (off) - * \li 1.490ms = the "low end" of the deadband range - * \li 1.026ms = full "reverse" - */ -class Victor : public PWMMotorController { - public: - /** - * Constructor for a Victor 888 connected via PWM. - * - * @param channel The PWM channel that the Victor 888 is attached to. 0-9 are - * on-board, 10-19 are on the MXP port - */ - explicit Victor(int channel); - - Victor(Victor&&) = default; - Victor& operator=(Victor&&) = default; -}; - -} // namespace frc diff --git a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp deleted file mode 100644 index 5acf3c818d..0000000000 --- a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp +++ /dev/null @@ -1,86 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "frc/motorcontrol/NidecBrushless.h" - -#include - -#include -#include -#include -#include - -using namespace frc; - -WPI_IGNORE_DEPRECATED - -NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel) - : m_dio(dioChannel), m_pwm(pwmChannel) { - wpi::SendableRegistry::AddChild(this, &m_dio); - wpi::SendableRegistry::AddChild(this, &m_pwm); - SetExpiration(0_s); - SetSafetyEnabled(false); - - // the dio controls the output (in PWM mode) - m_dio.SetPWMRate(15625); - m_dio.EnablePWM(0.5); - - HAL_Report(HALUsageReporting::kResourceType_NidecBrushless, pwmChannel + 1); - wpi::SendableRegistry::AddLW(this, "Nidec Brushless", pwmChannel); -} - -WPI_UNIGNORE_DEPRECATED - -void NidecBrushless::Set(double speed) { - if (!m_disabled) { - m_speed = speed; - m_dio.UpdateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed)); - m_pwm.SetAlwaysHighMode(); - } - Feed(); -} - -double NidecBrushless::Get() const { - return m_speed; -} - -void NidecBrushless::SetInverted(bool isInverted) { - m_isInverted = isInverted; -} - -bool NidecBrushless::GetInverted() const { - return m_isInverted; -} - -void NidecBrushless::Disable() { - m_disabled = true; - m_dio.UpdateDutyCycle(0.5); - m_pwm.SetDisabled(); -} - -void NidecBrushless::Enable() { - m_disabled = false; -} - -void NidecBrushless::StopMotor() { - m_dio.UpdateDutyCycle(0.5); - m_pwm.SetDisabled(); -} - -std::string NidecBrushless::GetDescription() const { - return fmt::format("Nidec {}", GetChannel()); -} - -int NidecBrushless::GetChannel() const { - return m_pwm.GetChannel(); -} - -void NidecBrushless::InitSendable(wpi::SendableBuilder& builder) { - builder.SetSmartDashboardType("Nidec Brushless"); - builder.SetActuator(true); - builder.SetSafeState([=, this] { StopMotor(); }); - builder.AddDoubleProperty( - "Value", [=, this] { return Get(); }, - [=, this](double value) { Set(value); }); -} diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h b/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h deleted file mode 100644 index d50c836170..0000000000 --- a/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h +++ /dev/null @@ -1,103 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include - -#include -#include -#include - -#include "frc/DigitalOutput.h" -#include "frc/MotorSafety.h" -#include "frc/PWM.h" -#include "frc/motorcontrol/MotorController.h" - -namespace frc { - -WPI_IGNORE_DEPRECATED - -/** - * Nidec Brushless Motor. - */ -class NidecBrushless : public MotorController, - public MotorSafety, - public wpi::Sendable, - public wpi::SendableHelper { - public: - /** - * Constructor. - * - * @param pwmChannel The PWM channel that the Nidec Brushless controller is - * attached to. 0-9 are on-board, 10-19 are on the MXP port. - * @param dioChannel The DIO channel that the Nidec Brushless controller is - * attached to. 0-9 are on-board, 10-25 are on the MXP port. - */ - NidecBrushless(int pwmChannel, int dioChannel); - - ~NidecBrushless() override = default; - - NidecBrushless(NidecBrushless&&) = default; - NidecBrushless& operator=(NidecBrushless&&) = default; - - // MotorController interface - /** - * Set the PWM value. - * - * The PWM value is set using a range of -1.0 to 1.0, appropriately scaling - * the value for the FPGA. - * - * @param speed The speed value between -1.0 and 1.0 to set. - */ - void Set(double speed) override; - - /** - * Get the recently set value of the PWM. - * - * @return The most recently set value for the PWM between -1.0 and 1.0. - */ - double Get() const override; - - void SetInverted(bool isInverted) override; - - bool GetInverted() const override; - - /** - * Disable the motor. The Enable() function must be called to re-enable the - * motor. - */ - void Disable() override; - - /** - * Re-enable the motor after Disable() has been called. The Set() function - * must be called to set a new motor speed. - */ - void Enable(); - - // MotorSafety interface - void StopMotor() override; - std::string GetDescription() const override; - - /** - * Gets the channel number associated with the object. - * - * @return The channel number. - */ - int GetChannel() const; - - // Sendable interface - void InitSendable(wpi::SendableBuilder& builder) override; - - private: - bool m_isInverted = false; - bool m_disabled = false; - DigitalOutput m_dio; - PWM m_pwm; - double m_speed = 0.0; -}; - -WPI_UNIGNORE_DEPRECATED - -} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h b/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h index d7ed1d5751..654c27e990 100644 --- a/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h +++ b/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h @@ -204,14 +204,10 @@ enum class BuiltInWidgets { * The motor controller will be controllable from the dashboard when test mode * is enabled, but will otherwise be view-only.
Supported types:

    *
  • PWMMotorController
  • - *
  • DMC60
  • - *
  • Jaguar
  • *
  • PWMTalonSRX
  • *
  • PWMVictorSPX
  • - *
  • SD540
  • *
  • Spark
  • *
  • Talon
  • - *
  • Victor
  • *
  • VictorSP
  • *
  • MotorControllerGroup
  • *
  • Any custom subclass of {@code SpeedContorller}
  • diff --git a/wpilibcIntegrationTests/src/main/native/cpp/CounterTest.cpp b/wpilibcIntegrationTests/src/main/native/cpp/CounterTest.cpp index e562d6af80..a47d4b3d4e 100644 --- a/wpilibcIntegrationTests/src/main/native/cpp/CounterTest.cpp +++ b/wpilibcIntegrationTests/src/main/native/cpp/CounterTest.cpp @@ -9,9 +9,7 @@ #include "TestBench.h" #include "frc/Timer.h" -#include "frc/motorcontrol/Jaguar.h" #include "frc/motorcontrol/Talon.h" -#include "frc/motorcontrol/Victor.h" static constexpr auto kMotorDelay = 2.5_s; @@ -23,8 +21,8 @@ class CounterTest : public testing::Test { frc::Counter m_victorCounter{TestBench::kVictorEncoderChannelA}; frc::Counter m_jaguarCounter{TestBench::kJaguarEncoderChannelA}; frc::Talon m_talon{TestBench::kVictorChannel}; - frc::Victor m_victor{TestBench::kTalonChannel}; - frc::Jaguar m_jaguar{TestBench::kJaguarChannel}; + frc::Talon m_victor{TestBench::kTalonChannel}; + frc::Talon m_jaguar{TestBench::kJaguarChannel}; void Reset() { m_talonCounter.Reset(); diff --git a/wpilibcIntegrationTests/src/main/native/cpp/DMATest.cpp b/wpilibcIntegrationTests/src/main/native/cpp/DMATest.cpp index 35d94b5549..61211acbe1 100644 --- a/wpilibcIntegrationTests/src/main/native/cpp/DMATest.cpp +++ b/wpilibcIntegrationTests/src/main/native/cpp/DMATest.cpp @@ -13,7 +13,7 @@ #include "frc/DMASample.h" #include "frc/DigitalOutput.h" #include "frc/Timer.h" -#include "frc/motorcontrol/Jaguar.h" +#include "frc/motorcontrol/Talon.h" using namespace frc; @@ -24,7 +24,7 @@ class DMATest : public testing::Test { AnalogInput m_analogInput{TestBench::kAnalogOutputChannel}; AnalogOutput m_analogOutput{TestBench::kFakeAnalogOutputChannel}; DigitalOutput m_manualTrigger{TestBench::kLoop1InputChannel}; - Jaguar m_pwm{TestBench::kFakePwmOutput}; + Talon m_pwm{TestBench::kFakePwmOutput}; DMA m_dma; void SetUp() override { diff --git a/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp b/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp index 949950472c..1a65a301fc 100644 --- a/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp +++ b/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp @@ -14,9 +14,7 @@ #include "frc/Timer.h" #include "frc/controller/PIDController.h" #include "frc/filter/LinearFilter.h" -#include "frc/motorcontrol/Jaguar.h" #include "frc/motorcontrol/Talon.h" -#include "frc/motorcontrol/Victor.h" enum MotorEncoderTestType { TEST_VICTOR, TEST_JAGUAR, TEST_TALON }; @@ -53,13 +51,13 @@ class MotorEncoderTest : public testing::TestWithParam { MotorEncoderTest() { switch (GetParam()) { case TEST_VICTOR: - m_motorController = new frc::Victor(TestBench::kVictorChannel); + m_motorController = new frc::Talon(TestBench::kVictorChannel); m_encoder = new frc::Encoder(TestBench::kVictorEncoderChannelA, TestBench::kVictorEncoderChannelB); break; case TEST_JAGUAR: - m_motorController = new frc::Jaguar(TestBench::kJaguarChannel); + m_motorController = new frc::Talon(TestBench::kJaguarChannel); m_encoder = new frc::Encoder(TestBench::kJaguarEncoderChannelA, TestBench::kJaguarEncoderChannelB); break; diff --git a/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp b/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp index 49a419c10d..92f2e447f5 100644 --- a/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp +++ b/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp @@ -9,9 +9,7 @@ #include "TestBench.h" #include "frc/Encoder.h" #include "frc/Timer.h" -#include "frc/motorcontrol/Jaguar.h" #include "frc/motorcontrol/Talon.h" -#include "frc/motorcontrol/Victor.h" enum MotorInvertingTestType { TEST_VICTOR, TEST_JAGUAR, TEST_TALON }; @@ -45,13 +43,13 @@ class MotorInvertingTest MotorInvertingTest() { switch (GetParam()) { case TEST_VICTOR: - m_motorController = new frc::Victor(TestBench::kVictorChannel); + m_motorController = new frc::Talon(TestBench::kVictorChannel); m_encoder = new frc::Encoder(TestBench::kVictorEncoderChannelA, TestBench::kVictorEncoderChannelB); break; case TEST_JAGUAR: - m_motorController = new frc::Jaguar(TestBench::kJaguarChannel); + m_motorController = new frc::Talon(TestBench::kJaguarChannel); m_encoder = new frc::Encoder(TestBench::kJaguarEncoderChannelA, TestBench::kJaguarEncoderChannelB); break; diff --git a/wpilibj/src/generate/pwm_motor_controllers.json b/wpilibj/src/generate/pwm_motor_controllers.json index c04935fba1..dab2a74870 100644 --- a/wpilibj/src/generate/pwm_motor_controllers.json +++ b/wpilibj/src/generate/pwm_motor_controllers.json @@ -1,30 +1,4 @@ [ - { - "name": "DMC60", - "Manufacturer": "Digilent", - "DisplayName": "DMC 60", - "ResourceName": "DigilentDMC60", - "pulse_width_ms": { - "max": 2.004, - "deadbandMax": 1.520, - "center": 1.500, - "deadbandMin": 1.480, - "min": 0.997 - } - }, - { - "name": "Jaguar", - "Manufacturer": "Luminary Micro / Vex Robotics", - "DisplayName": "Jaguar", - "ResourceName": "Jaguar", - "pulse_width_ms": { - "max": 2.310, - "deadbandMax": 1.550, - "center": 1.507, - "deadbandMin": 1.454, - "min": 0.697 - } - }, { "name": "PWMSparkFlex", "Manufacturer": "REV Robotics", @@ -103,19 +77,6 @@ "min": 0.997 } }, - { - "name": "SD540", - "Manufacturer": "Mindsensors", - "DisplayName": "SD540", - "ResourceName": "MindsensorsSD540", - "pulse_width_ms": { - "max": 2.05, - "deadbandMax": 1.55, - "center": 1.50, - "deadbandMin": 1.44, - "min": 0.94 - } - }, { "name": "Spark", "Manufacturer": "REV Robotics", @@ -142,20 +103,6 @@ "min": 0.989 } }, - { - "name": "Victor", - "Manufacturer": "Vex Robotics", - "DisplayName": "Victor 888", - "ResourceName": "Victor", - "PeriodMultiplier": 2, - "pulse_width_ms": { - "max": 2.027, - "deadbandMax": 1.525, - "center": 1.507, - "deadbandMin": 1.490, - "min": 1.026 - } - }, { "name": "VictorSP", "Manufacturer": "Vex Robotics", diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java deleted file mode 100644 index 25e11c159b..0000000000 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java +++ /dev/null @@ -1,48 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY - -package edu.wpi.first.wpilibj.motorcontrol; - -import edu.wpi.first.hal.FRCNetComm.tResourceType; -import edu.wpi.first.hal.HAL; -import edu.wpi.first.wpilibj.PWM; - -/** - * Digilent DMC 60 Motor Controller. - * - *

    Note that the DMC 60 uses the following bounds for PWM values. These values should work - * reasonably well for most controllers, but if users experience issues such as asymmetric behavior - * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the DMC 60 User Manual available from - * Digilent. - * - *

      - *
    • 2.004ms = full "forward" - *
    • 1.520ms = the "high end" of the deadband range - *
    • 1.500ms = center of the deadband range (off) - *
    • 1.480ms = the "low end" of the deadband range - *
    • 0.997ms = full "reverse" - *
    - */ -public class DMC60 extends PWMMotorController { - /** - * Constructor. - * - * @param channel The PWM channel that the DMC 60 is attached to. 0-9 are on-board, 10-19 - * are on the MXP port - */ - @SuppressWarnings("this-escape") - public DMC60(final int channel) { - super("DMC60", channel); - - m_pwm.setBoundsMicroseconds(2004, 1520, 1500, 1480, 997); - m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X); - m_pwm.setSpeed(0.0); - m_pwm.setZeroLatch(); - - HAL.report(tResourceType.kResourceType_DigilentDMC60, getChannel() + 1); - } -} diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java deleted file mode 100644 index d9638942a3..0000000000 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java +++ /dev/null @@ -1,48 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY - -package edu.wpi.first.wpilibj.motorcontrol; - -import edu.wpi.first.hal.FRCNetComm.tResourceType; -import edu.wpi.first.hal.HAL; -import edu.wpi.first.wpilibj.PWM; - -/** - * Luminary Micro / Vex Robotics Jaguar Motor Controller. - * - *

    Note that the Jaguar uses the following bounds for PWM values. These values should work - * reasonably well for most controllers, but if users experience issues such as asymmetric behavior - * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the Jaguar User Manual available from - * Luminary Micro / Vex Robotics. - * - *

      - *
    • 2.310ms = full "forward" - *
    • 1.550ms = the "high end" of the deadband range - *
    • 1.507ms = center of the deadband range (off) - *
    • 1.454ms = the "low end" of the deadband range - *
    • 0.697ms = full "reverse" - *
    - */ -public class Jaguar extends PWMMotorController { - /** - * Constructor. - * - * @param channel The PWM channel that the Jaguar is attached to. 0-9 are on-board, 10-19 - * are on the MXP port - */ - @SuppressWarnings("this-escape") - public Jaguar(final int channel) { - super("Jaguar", channel); - - m_pwm.setBoundsMicroseconds(2310, 1550, 1507, 1454, 697); - m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X); - m_pwm.setSpeed(0.0); - m_pwm.setZeroLatch(); - - HAL.report(tResourceType.kResourceType_Jaguar, getChannel() + 1); - } -} diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java deleted file mode 100644 index 1ee4eebc00..0000000000 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java +++ /dev/null @@ -1,48 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY - -package edu.wpi.first.wpilibj.motorcontrol; - -import edu.wpi.first.hal.FRCNetComm.tResourceType; -import edu.wpi.first.hal.HAL; -import edu.wpi.first.wpilibj.PWM; - -/** - * Mindsensors SD540 Motor Controller. - * - *

    Note that the SD540 uses the following bounds for PWM values. These values should work - * reasonably well for most controllers, but if users experience issues such as asymmetric behavior - * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the SD540 User Manual available from - * Mindsensors. - * - *

      - *
    • 2.050ms = full "forward" - *
    • 1.550ms = the "high end" of the deadband range - *
    • 1.500ms = center of the deadband range (off) - *
    • 1.440ms = the "low end" of the deadband range - *
    • 0.940ms = full "reverse" - *
    - */ -public class SD540 extends PWMMotorController { - /** - * Constructor. - * - * @param channel The PWM channel that the SD540 is attached to. 0-9 are on-board, 10-19 - * are on the MXP port - */ - @SuppressWarnings("this-escape") - public SD540(final int channel) { - super("SD540", channel); - - m_pwm.setBoundsMicroseconds(2050, 1550, 1500, 1440, 940); - m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X); - m_pwm.setSpeed(0.0); - m_pwm.setZeroLatch(); - - HAL.report(tResourceType.kResourceType_MindsensorsSD540, getChannel() + 1); - } -} diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java deleted file mode 100644 index 6c6a0c21b0..0000000000 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java +++ /dev/null @@ -1,48 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY - -package edu.wpi.first.wpilibj.motorcontrol; - -import edu.wpi.first.hal.FRCNetComm.tResourceType; -import edu.wpi.first.hal.HAL; -import edu.wpi.first.wpilibj.PWM; - -/** - * Vex Robotics Victor 888 Motor Controller. - * - *

    Note that the Victor 888 uses the following bounds for PWM values. These values should work - * reasonably well for most controllers, but if users experience issues such as asymmetric behavior - * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the Victor 888 User Manual available from - * Vex Robotics. - * - *

      - *
    • 2.027ms = full "forward" - *
    • 1.525ms = the "high end" of the deadband range - *
    • 1.507ms = center of the deadband range (off) - *
    • 1.490ms = the "low end" of the deadband range - *
    • 1.026ms = full "reverse" - *
    - */ -public class Victor extends PWMMotorController { - /** - * Constructor. - * - * @param channel The PWM channel that the Victor 888 is attached to. 0-9 are on-board, 10-19 - * are on the MXP port - */ - @SuppressWarnings("this-escape") - public Victor(final int channel) { - super("Victor", channel); - - m_pwm.setBoundsMicroseconds(2027, 1525, 1507, 1490, 1026); - m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k2X); - m_pwm.setSpeed(0.0); - m_pwm.setZeroLatch(); - - HAL.report(tResourceType.kResourceType_Victor, getChannel() + 1); - } -} diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java deleted file mode 100644 index 01af76563c..0000000000 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java +++ /dev/null @@ -1,145 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package edu.wpi.first.wpilibj.motorcontrol; - -import edu.wpi.first.hal.FRCNetComm.tResourceType; -import edu.wpi.first.hal.HAL; -import edu.wpi.first.util.sendable.Sendable; -import edu.wpi.first.util.sendable.SendableBuilder; -import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.DigitalOutput; -import edu.wpi.first.wpilibj.MotorSafety; -import edu.wpi.first.wpilibj.PWM; - -/** Nidec Brushless Motor. */ -@SuppressWarnings("removal") -public class NidecBrushless extends MotorSafety - implements MotorController, Sendable, AutoCloseable { - private boolean m_isInverted; - private final DigitalOutput m_dio; - private final PWM m_pwm; - private volatile double m_speed; - private volatile boolean m_disabled; - - /** - * Constructor. - * - * @param pwmChannel The PWM channel that the Nidec Brushless controller is attached to. 0-9 are - * on-board, 10-19 are on the MXP port - * @param dioChannel The DIO channel that the Nidec Brushless controller is attached to. 0-9 are - * on-board, 10-25 are on the MXP port - */ - @SuppressWarnings("this-escape") - public NidecBrushless(final int pwmChannel, final int dioChannel) { - setSafetyEnabled(false); - - // the dio controls the output (in PWM mode) - m_dio = new DigitalOutput(dioChannel); - SendableRegistry.addChild(this, m_dio); - m_dio.setPWMRate(15625); - m_dio.enablePWM(0.5); - - // the pwm enables the controller - m_pwm = new PWM(pwmChannel); - SendableRegistry.addChild(this, m_pwm); - - HAL.report(tResourceType.kResourceType_NidecBrushless, pwmChannel + 1); - SendableRegistry.addLW(this, "Nidec Brushless", pwmChannel); - } - - @Override - public void close() { - SendableRegistry.remove(this); - m_dio.close(); - m_pwm.close(); - } - - /** - * Set the PWM value. - * - *

    The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the - * FPGA. - * - * @param speed The speed value between -1.0 and 1.0 to set. - */ - @Override - public void set(double speed) { - if (!m_disabled) { - m_speed = speed; - m_dio.updateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed)); - m_pwm.setAlwaysHighMode(); - } - - feed(); - } - - /** - * Get the recently set value of the PWM. - * - * @return The most recently set value for the PWM between -1.0 and 1.0. - */ - @Override - public double get() { - return m_speed; - } - - @Override - public void setInverted(boolean isInverted) { - m_isInverted = isInverted; - } - - @Override - public boolean getInverted() { - return m_isInverted; - } - - /** - * Stop the motor. This is called by the MotorSafety object when it has a timeout for this PWM and - * needs to stop it from running. Calling set() will re-enable the motor. - */ - @Override - public void stopMotor() { - m_dio.updateDutyCycle(0.5); - m_pwm.setDisabled(); - } - - @Override - public String getDescription() { - return "Nidec " + getChannel(); - } - - /** Disable the motor. The enable() function must be called to re-enable the motor. */ - @Override - public void disable() { - m_disabled = true; - m_dio.updateDutyCycle(0.5); - m_pwm.setDisabled(); - } - - /** - * Re-enable the motor after disable() has been called. The set() function must be called to set a - * new motor speed. - */ - public void enable() { - m_disabled = false; - } - - /** - * Gets the channel number associated with the object. - * - * @return The channel number. - */ - public int getChannel() { - return m_pwm.getChannel(); - } - - @Override - public void initSendable(SendableBuilder builder) { - builder.setSmartDashboardType("Nidec Brushless"); - builder.setActuator(true); - builder.setSafeState(this::stopMotor); - builder.addDoubleProperty("Value", this::get, this::set); - } -} diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java index c034a4a433..33017321c6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java @@ -250,17 +250,13 @@ public enum BuiltInWidgets implements WidgetType { * *

      *
    • {@link edu.wpi.first.wpilibj.motorcontrol.PWMMotorController} - *
    • {@link edu.wpi.first.wpilibj.motorcontrol.DMC60} - *
    • {@link edu.wpi.first.wpilibj.motorcontrol.Jaguar} *
    • {@link edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax} *
    • {@link edu.wpi.first.wpilibj.motorcontrol.PWMTalonFX} *
    • {@link edu.wpi.first.wpilibj.motorcontrol.PWMTalonSRX} *
    • {@link edu.wpi.first.wpilibj.motorcontrol.PWMVenom} *
    • {@link edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX} - *
    • {@link edu.wpi.first.wpilibj.motorcontrol.SD540} *
    • {@link edu.wpi.first.wpilibj.motorcontrol.Spark} *
    • {@link edu.wpi.first.wpilibj.motorcontrol.Talon} - *
    • {@link edu.wpi.first.wpilibj.motorcontrol.Victor} *
    • {@link edu.wpi.first.wpilibj.motorcontrol.VictorSP} *
    • {@link edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup} *
    • Any custom subclass of {@code MotorController} diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DMATest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DMATest.java index 1da5c6fe81..964d762813 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DMATest.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DMATest.java @@ -9,8 +9,8 @@ import static org.junit.Assert.assertTrue; import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.fixtures.AnalogCrossConnectFixture; -import edu.wpi.first.wpilibj.motorcontrol.Jaguar; import edu.wpi.first.wpilibj.motorcontrol.PWMMotorController; +import edu.wpi.first.wpilibj.motorcontrol.Talon; import edu.wpi.first.wpilibj.test.AbstractComsSetup; import edu.wpi.first.wpilibj.test.TestBench; import java.util.ArrayList; @@ -40,7 +40,7 @@ public class DMATest extends AbstractComsSetup { public void setUp() { m_analogIO = TestBench.getAnalogCrossConnectFixture(); m_manualTrigger = new DigitalOutput(7); - m_pwm = new Jaguar(14); + m_pwm = new Talon(14); m_dma = new DMA(); m_dmaSample = new DMASample(); diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java index cba5a35713..eaf675e3cf 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java @@ -15,9 +15,7 @@ import edu.wpi.first.wpilibj.fixtures.DIOCrossConnectFixture; import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture; import edu.wpi.first.wpilibj.fixtures.RelayCrossConnectFixture; import edu.wpi.first.wpilibj.fixtures.TiltPanCameraFixture; -import edu.wpi.first.wpilibj.motorcontrol.Jaguar; import edu.wpi.first.wpilibj.motorcontrol.Talon; -import edu.wpi.first.wpilibj.motorcontrol.Victor; import java.io.PrintStream; import java.util.ArrayList; import java.util.Collection; @@ -92,16 +90,16 @@ public final class TestBench { } /** - * Constructs a new set of objects representing a connected set of Victor controlled Motors and an + * Constructs a new set of objects representing a connected set of Talon controlled Motors and an * encoder. * - * @return a freshly allocated Victor, Encoder pair + * @return a freshly allocated Talon, Encoder pair */ - public static MotorEncoderFixture getVictorPair() { + public static MotorEncoderFixture getVictorPair() { return new MotorEncoderFixture<>() { @Override - protected Victor giveMotorController() { - return new Victor(kVictorChannel); + protected Talon giveMotorController() { + return new Talon(kVictorChannel); } @Override @@ -122,16 +120,16 @@ public final class TestBench { } /** - * Constructs a new set of objects representing a connected set of Jaguar controlled Motors and an + * Constructs a new set of objects representing a connected set of Talon controlled Motors and an * encoder. * - * @return a freshly allocated Jaguar, Encoder pair + * @return a freshly allocated Talon, Encoder pair */ - public static MotorEncoderFixture getJaguarPair() { + public static MotorEncoderFixture getJaguarPair() { return new MotorEncoderFixture<>() { @Override - protected Jaguar giveMotorController() { - return new Jaguar(kJaguarChannel); + protected Talon giveMotorController() { + return new Talon(kJaguarChannel); } @Override From 8b99ad82c3736490567a03706f02b0daaff8caa6 Mon Sep 17 00:00:00 2001 From: Murat65536 <99989538+Murat65536@users.noreply.github.com> Date: Wed, 29 Oct 2025 03:18:55 +0000 Subject: [PATCH 06/10] [wpilib] Add a few unit overloads (#8231) Co-authored-by: Sam Carlberg Co-authored-by: Joseph Eng <91924258+KangarooKoala@users.noreply.github.com> Co-authored-by: Tyler Veness --- wpilibc/src/main/native/cpp/Notifier.cpp | 4 ++ wpilibc/src/main/native/cpp/TimedRobot.cpp | 2 + .../src/main/native/include/frc/Notifier.h | 12 ++++++ .../src/main/native/include/frc/TimedRobot.h | 10 ++++- .../java/edu/wpi/first/wpilibj/Notifier.java | 38 +++++++++++++++++++ .../edu/wpi/first/wpilibj/TimedRobot.java | 21 +++++++++- .../java/edu/wpi/first/wpilibj/Timer.java | 34 ++++++++++++++--- .../java/edu/wpi/first/wpilibj/Watchdog.java | 13 +++++++ .../wpi/first/wpilibj/event/BooleanEvent.java | 29 +++++++++++++- .../first/wpilibj/smartdashboard/Field2d.java | 14 +++++++ .../wpilibj/smartdashboard/FieldObject2d.java | 14 +++++++ 11 files changed, 182 insertions(+), 9 deletions(-) diff --git a/wpilibc/src/main/native/cpp/Notifier.cpp b/wpilibc/src/main/native/cpp/Notifier.cpp index 9536acc7e1..aa78381551 100644 --- a/wpilibc/src/main/native/cpp/Notifier.cpp +++ b/wpilibc/src/main/native/cpp/Notifier.cpp @@ -182,6 +182,10 @@ void Notifier::StartPeriodic(units::second_t period) { UpdateAlarm(); } +void Notifier::StartPeriodic(units::hertz_t frequency) { + StartPeriodic(1 / frequency); +} + void Notifier::Stop() { std::scoped_lock lock(m_processMutex); m_periodic = false; diff --git a/wpilibc/src/main/native/cpp/TimedRobot.cpp b/wpilibc/src/main/native/cpp/TimedRobot.cpp index d2c39d12c5..58b8c2cde1 100644 --- a/wpilibc/src/main/native/cpp/TimedRobot.cpp +++ b/wpilibc/src/main/native/cpp/TimedRobot.cpp @@ -91,6 +91,8 @@ TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) { HALUsageReporting::kFramework_Timed); } +TimedRobot::TimedRobot(units::hertz_t frequency) : TimedRobot{1 / frequency} {} + TimedRobot::~TimedRobot() { if (m_notifier != HAL_kInvalidHandle) { int32_t status = 0; diff --git a/wpilibc/src/main/native/include/frc/Notifier.h b/wpilibc/src/main/native/include/frc/Notifier.h index 2841be4834..ea5b67fd58 100644 --- a/wpilibc/src/main/native/include/frc/Notifier.h +++ b/wpilibc/src/main/native/include/frc/Notifier.h @@ -14,6 +14,7 @@ #include #include +#include #include #include @@ -107,6 +108,17 @@ class Notifier { */ void StartPeriodic(units::second_t period); + /** + * Run the callback periodically with the given frequency. + * + * The user-provided callback should be written so that it completes before + * the next time it's scheduled to run. + * + * @param frequency Frequency after which to call the callback starting one + * period after the call to this method. + */ + void StartPeriodic(units::hertz_t frequency); + /** * Stop further callback invocations. * diff --git a/wpilibc/src/main/native/include/frc/TimedRobot.h b/wpilibc/src/main/native/include/frc/TimedRobot.h index 15afe34acb..9d1e8ca1a1 100644 --- a/wpilibc/src/main/native/include/frc/TimedRobot.h +++ b/wpilibc/src/main/native/include/frc/TimedRobot.h @@ -11,6 +11,7 @@ #include #include +#include #include #include #include @@ -47,10 +48,17 @@ class TimedRobot : public IterativeRobotBase { /** * Constructor for TimedRobot. * - * @param period Period. + * @param period The period of the robot loop function. */ explicit TimedRobot(units::second_t period = kDefaultPeriod); + /** + * Constructor for TimedRobot. + * + * @param frequency The frequency of the robot loop function. + */ + explicit TimedRobot(units::hertz_t frequency); + TimedRobot(TimedRobot&&) = default; TimedRobot& operator=(TimedRobot&&) = default; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java index 54aeaddea1..f91a057a0b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java @@ -4,9 +4,12 @@ package edu.wpi.first.wpilibj; +import static edu.wpi.first.units.Units.Seconds; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.hal.NotifierJNI; +import edu.wpi.first.units.measure.Frequency; +import edu.wpi.first.units.measure.Time; import java.util.concurrent.atomic.AtomicInteger; import java.util.concurrent.locks.ReentrantLock; @@ -186,6 +189,15 @@ public class Notifier implements AutoCloseable { } } + /** + * Run the callback once after the given delay. + * + * @param delay Time to wait before the callback is called. + */ + public void startSingle(Time delay) { + startSingle(delay.in(Seconds)); + } + /** * Run the callback periodically with the given period. * @@ -207,6 +219,32 @@ public class Notifier implements AutoCloseable { } } + /** + * Run the callback periodically with the given period. + * + *

      The user-provided callback should be written so that it completes before the next time it's + * scheduled to run. + * + * @param period Period after which to call the callback starting one period after the call to + * this method. + */ + public void startPeriodic(Time period) { + startPeriodic(period.in(Seconds)); + } + + /** + * Run the callback periodically with the given frequency. + * + *

      The user-provided callback should be written so that it completes before the next time it's + * scheduled to run. + * + * @param frequency Frequency at which to call the callback, starting one period after the call to + * this method. + */ + public void startPeriodic(Frequency frequency) { + startPeriodic(frequency.asPeriod()); + } + /** * Stop further callback invocations. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java index 4525d6aa65..de0fab0f26 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java @@ -11,6 +11,7 @@ import edu.wpi.first.hal.FRCNetComm.tInstances; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.NotifierJNI; +import edu.wpi.first.units.measure.Frequency; import edu.wpi.first.units.measure.Time; import java.util.PriorityQueue; @@ -84,7 +85,7 @@ public class TimedRobot extends IterativeRobotBase { /** * Constructor for TimedRobot. * - * @param period Period in seconds. + * @param period The period of the robot loop function. */ protected TimedRobot(double period) { super(period); @@ -95,6 +96,24 @@ public class TimedRobot extends IterativeRobotBase { HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Timed); } + /** + * Constructor for TimedRobot. + * + * @param period The period of the robot loop function. + */ + protected TimedRobot(Time period) { + this(period.in(Seconds)); + } + + /** + * Constructor for TimedRobot. + * + * @param frequency The frequency of the robot loop function. + */ + protected TimedRobot(Frequency frequency) { + this(frequency.asPeriod()); + } + @Override public void close() { NotifierJNI.stopNotifier(m_notifier); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java index fb92dc52a8..af55a43208 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java @@ -4,6 +4,10 @@ package edu.wpi.first.wpilibj; +import static edu.wpi.first.units.Units.Seconds; + +import edu.wpi.first.units.measure.Time; + /** * A timer class. * @@ -46,10 +50,20 @@ public class Timer { } /** - * Pause the thread for a specified time. Pause the execution of the thread for a specified period - * of time given in seconds. Motors will continue to run at their last assigned values, and - * sensors will continue to update. Only the task containing the wait will pause until the wait - * time is expired. + * Pause the execution of the thread for a specified period of time. Motors will continue to run + * at their last assigned values, and sensors will continue to update. Only the task containing + * the wait will pause until the wait time is expired. + * + * @param period Length of time to pause + */ + public static void delay(final Time period) { + delay(period.in(Seconds)); + } + + /** + * Pause the execution of the thread for a specified period of time given in seconds. Motors will + * continue to run at their last assigned values, and sensors will continue to update. Only the + * task containing the wait will pause until the wait time is expired. * * @param seconds Length of time to pause */ @@ -137,7 +151,17 @@ public class Timer { /** * Check if the period specified has passed. * - * @param seconds The period to check. + * @param period The period to check. + * @return Whether the period has passed. + */ + public boolean hasElapsed(Time period) { + return hasElapsed(period.in(Seconds)); + } + + /** + * Check if the period specified has passed. + * + * @param seconds The period to check in seconds. * @return Whether the period has passed. */ public boolean hasElapsed(double seconds) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java index 6d00d6402b..e3373c844a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java @@ -4,7 +4,10 @@ package edu.wpi.first.wpilibj; +import static edu.wpi.first.units.Units.Seconds; + import edu.wpi.first.hal.NotifierJNI; +import edu.wpi.first.units.measure.Time; import java.io.Closeable; import java.util.PriorityQueue; import java.util.concurrent.locks.ReentrantLock; @@ -55,6 +58,16 @@ public class Watchdog implements Closeable, Comparable { m_tracer = new Tracer(); } + /** + * Watchdog constructor. + * + * @param timeout The watchdog's timeout with microsecond resolution. + * @param callback This function is called when the timeout expires. + */ + public Watchdog(Time timeout, Runnable callback) { + this(timeout.in(Seconds), callback); + } + @Override public void close() { disable(); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java index 9369b7811a..01c0b8ee3b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java @@ -4,9 +4,11 @@ package edu.wpi.first.wpilibj.event; +import static edu.wpi.first.units.Units.Seconds; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.math.filter.Debouncer; +import edu.wpi.first.units.measure.Time; import java.util.concurrent.atomic.AtomicBoolean; import java.util.function.BiFunction; import java.util.function.BooleanSupplier; @@ -167,7 +169,18 @@ public class BooleanEvent implements BooleanSupplier { * Creates a new debounced event from this event - it will become active when this event has been * active for longer than the specified period. * - * @param seconds The debounce period. + * @param period The debounce period. + * @return The debounced event (rising edges debounced only). + */ + public BooleanEvent debounce(Time period) { + return debounce(period.in(Seconds)); + } + + /** + * Creates a new debounced event from this event - it will become active when this event has been + * active for longer than the specified period. + * + * @param seconds The debounce period in seconds. * @return The debounced event (rising edges debounced only). */ public BooleanEvent debounce(double seconds) { @@ -178,7 +191,19 @@ public class BooleanEvent implements BooleanSupplier { * Creates a new debounced event from this event - it will become active when this event has been * active for longer than the specified period. * - * @param seconds The debounce period. + * @param period The debounce period. + * @param type The debounce type. + * @return The debounced event. + */ + public BooleanEvent debounce(Time period, Debouncer.DebounceType type) { + return debounce(period.in(Seconds), type); + } + + /** + * Creates a new debounced event from this event - it will become active when this event has been + * active for longer than the specified period. + * + * @param seconds The debounce period in seconds. * @param type The debounce type. * @return The debounced event. */ diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java index 7ce6af8c3e..f3e09b5526 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java @@ -4,11 +4,14 @@ package edu.wpi.first.wpilibj.smartdashboard; +import static edu.wpi.first.units.Units.Meters; + import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.networktables.NTSendable; import edu.wpi.first.networktables.NTSendableBuilder; import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.units.measure.Distance; import edu.wpi.first.util.sendable.SendableRegistry; import java.util.ArrayList; import java.util.List; @@ -66,6 +69,17 @@ public class Field2d implements NTSendable, AutoCloseable { m_objects.get(0).setPose(xMeters, yMeters, rotation); } + /** + * Set the robot pose from x, y, and rotation. + * + * @param x X location + * @param y Y location + * @param rotation rotation + */ + public synchronized void setRobotPose(Distance x, Distance y, Rotation2d rotation) { + m_objects.get(0).setPose(x.in(Meters), y.in(Meters), rotation); + } + /** * Get the robot pose. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java index f3627a6bef..f9e38f9261 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java @@ -4,11 +4,14 @@ package edu.wpi.first.wpilibj.smartdashboard; +import static edu.wpi.first.units.Units.Meters; + import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.trajectory.Trajectory; import edu.wpi.first.networktables.DoubleArrayEntry; +import edu.wpi.first.units.measure.Distance; import java.util.ArrayList; import java.util.Collections; import java.util.List; @@ -51,6 +54,17 @@ public class FieldObject2d implements AutoCloseable { setPose(new Pose2d(xMeters, yMeters, rotation)); } + /** + * Set the pose from x, y, and rotation. + * + * @param x X location + * @param y Y location + * @param rotation rotation + */ + public synchronized void setPose(Distance x, Distance y, Rotation2d rotation) { + setPose(new Pose2d(x.in(Meters), y.in(Meters), rotation)); + } + /** * Get the pose. * From cd237e57d4987a5ca24c0e24f04c15cc35247682 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sat, 1 Nov 2025 09:17:09 -0700 Subject: [PATCH 07/10] [ci] Upgrade to macOS 15 runner image (#8321) This fixes a compiler bug (rejecting out-of-line definitions of constrained members) newer versions of Sleipnir were encountering. --- .github/workflows/bazel.yml | 2 +- .github/workflows/cmake.yml | 2 +- .github/workflows/gradle.yml | 10 +++++----- .github/workflows/sentinel-build.yml | 10 +++++----- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/.github/workflows/bazel.yml b/.github/workflows/bazel.yml index 3b93739f3a..bd5aedb6d2 100644 --- a/.github/workflows/bazel.yml +++ b/.github/workflows/bazel.yml @@ -37,7 +37,7 @@ jobs: build-mac: name: "Mac" - runs-on: macos-14 + runs-on: macOS-15 steps: - uses: actions/checkout@v4 with: { fetch-depth: 0 } diff --git a/.github/workflows/cmake.yml b/.github/workflows/cmake.yml index 82fdb8bc23..c7083911f4 100644 --- a/.github/workflows/cmake.yml +++ b/.github/workflows/cmake.yml @@ -20,7 +20,7 @@ jobs: name: Linux container: wpilib/roborio-cross-ubuntu:2025-22.04 flags: "--preset with-java-and-sccache -DCMAKE_BUILD_TYPE=Release -DWITH_EXAMPLES=ON" - - os: macOS-14 + - os: macOS-15 name: macOS container: "" env: "" diff --git a/.github/workflows/gradle.yml b/.github/workflows/gradle.yml index 145949908a..216873e2ca 100644 --- a/.github/workflows/gradle.yml +++ b/.github/workflows/gradle.yml @@ -98,7 +98,7 @@ jobs: build-options: "-PciReleaseOnly -Pbuildwinarm64 -Ponlywindowsarm64" task: "copyAllOutputs" outputs: "build/allOutputs" - - os: macOS-14 + - os: macOS-15 artifact-name: macOS architecture: aarch64 task: "build" @@ -153,7 +153,7 @@ jobs: if: matrix.os == 'windows-2022' - name: Check disk free space pre-cleanup (macOS) run: df -h . - if: matrix.os == 'macOS-14' + if: matrix.os == 'macOS-15' - name: Cleanup disk space # CodeQL: 5G # go: 748M @@ -162,10 +162,10 @@ jobs: rm -rf /Users/runner/hostedtoolcache/CodeQL rm -rf /Users/runner/hostedtoolcache/go rm -rf /Users/runner/Library/Android - if: matrix.os == 'macOS-14' + if: matrix.os == 'macOS-15' - name: Check disk free space post-cleanup (macOS) run: df -h . - if: matrix.os == 'macOS-14' + if: matrix.os == 'macOS-15' - name: Build with Gradle run: ./gradlew ${{ matrix.task }} --build-cache -PbuildServer -PskipJavaFormat ${{ matrix.build-options }} ${{ env.EXTRA_GRADLE_ARGS }} env: @@ -181,7 +181,7 @@ jobs: if: matrix.os == 'windows-2022' - name: Check disk free space (macOS) run: df -h . - if: matrix.os == 'macOS-14' + if: matrix.os == 'macOS-15' - uses: actions/upload-artifact@v4 with: name: ${{ matrix.artifact-name }} diff --git a/.github/workflows/sentinel-build.yml b/.github/workflows/sentinel-build.yml index c059efda2c..fc169f0c25 100644 --- a/.github/workflows/sentinel-build.yml +++ b/.github/workflows/sentinel-build.yml @@ -97,7 +97,7 @@ jobs: build-options: "-PciReleaseOnly -Pbuildwinarm64 -Ponlywindowsarm64" task: "copyAllOutputs" outputs: "build/allOutputs" - - os: macOS-14 + - os: macOS-15 artifact-name: macOS architecture: aarch64 task: "build" @@ -146,7 +146,7 @@ jobs: if: matrix.os == 'windows-2022' - name: Check disk free space pre-cleanup (macOS) run: df -h . - if: matrix.os == 'macOS-14' + if: matrix.os == 'macOS-15' - name: Cleanup disk space # CodeQL: 5G # go: 748M @@ -155,10 +155,10 @@ jobs: rm -rf /Users/runner/hostedtoolcache/CodeQL rm -rf /Users/runner/hostedtoolcache/go rm -rf /Users/runner/Library/Android - if: matrix.os == 'macOS-14' + if: matrix.os == 'macOS-15' - name: Check disk free space post-cleanup (macOS) run: df -h . - if: matrix.os == 'macOS-14' + if: matrix.os == 'macOS-15' - name: Build with Gradle run: ./gradlew ${{ matrix.task }} -PbuildServer -PskipJavaFormat ${{ matrix.build-options }} - name: Sign Libraries with Developer ID @@ -170,7 +170,7 @@ jobs: if: matrix.os == 'windows-2022' - name: Check disk free space (macOS) run: df -h . - if: matrix.os == 'macOS-14' + if: matrix.os == 'macOS-15' - uses: actions/upload-artifact@v4 with: name: ${{ matrix.artifact-name }} From b7fe5ef8330d6801d1bec93bfae697547e7c2952 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sat, 1 Nov 2025 09:18:50 -0700 Subject: [PATCH 08/10] [build] Fix up grammar in docs/build.gradle (#8317) --- docs/build.gradle | 21 +++++++++++++-------- 1 file changed, 13 insertions(+), 8 deletions(-) diff --git a/docs/build.gradle b/docs/build.gradle index 0e562b4f84..7071311dff 100644 --- a/docs/build.gradle +++ b/docs/build.gradle @@ -47,20 +47,25 @@ cppProjectZips.add(project(':romiVendordep').cppHeadersZip) cppProjectZips.add(project(':xrpVendordep').cppHeadersZip) doxygen { - // Doxygen binaries are only provided for x86_64 platforms - // Other platforms will need to provide doxygen via their system - // See below maven and https://doxygen.nl/download.html for provided binaries - // Ensure theme.css (from https://github.com/jothepro/doxygen-awesome-css) is compatible with - // doxygen version when updating + // Doxygen binaries are only provided for x86_64 platforms. Other platforms + // will need to use a local Doxygen install. + // + // executeByVersion() fetches Doxygen binaries from + // https://frcmaven.wpi.edu/ui/native/generic-release-mirror/doxygen/, which + // is a mirror of binaries from https://doxygen.nl/download.html. + // + // Ensure theme.css (from https://github.com/jothepro/doxygen-awesome-css) + // is compatible with Doxygen version when updating. executables { doxygen { - // Note: has no effect if not on an x86_64 platform - you need to have a global install available on your - // PATH for the doxygen plugin to run + // Note: has no effect if not on an x86_64 platform - you need to + // have a global install available on your PATH for the Doxygen + // plugin to run. executableByVersion('1.12.0') String arch = System.getProperty("os.arch"); if (!(arch.equals("x86_64") || arch.equals("amd64"))) { - // Search for a local doxygen install + // Search for a local Doxygen install executableBySearchPath('doxygen') } } From fea6883d98e0071b9d4ec7e17cccb6570910a72c Mon Sep 17 00:00:00 2001 From: Dalton Smith <105223895+daltzctr@users.noreply.github.com> Date: Sat, 1 Nov 2025 12:19:36 -0400 Subject: [PATCH 09/10] [wpimath] DCMotor: Add X44 and Minion (#8319) --- .../wpi/first/math/system/plant/DCMotor.java | 36 +++++++++++++++++++ .../native/include/frc/system/plant/DCMotor.h | 25 +++++++++++++ 2 files changed, 61 insertions(+) diff --git a/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java b/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java index de8346d7dd..dead6162f8 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java +++ b/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java @@ -310,6 +310,42 @@ public class DCMotor implements ProtobufSerializable, StructSerializable { 12, 9.37, 483, 2, Units.rotationsPerMinuteToRadiansPerSecond(5800), numMotors); } + /** + * Return a gearbox of Kraken X44 brushless motors. + * + * @param numMotors Number of motors in the gearbox. + * @return a gearbox of Kraken X44 motors. + */ + public static DCMotor getKrakenX44(int numMotors) { + // From https://motors.ctr-electronics.com/dyno/dynometer-testing/ + return new DCMotor( + 12, 4.11, 279, 2, Units.rotationsPerMinuteToRadiansPerSecond(7758), numMotors); + } + + /** + * Return a gearbox of Kraken X44 brushless motors with FOC (Field-Oriented Control) enabled. + * + * @param numMotors Number of motors in the gearbox. + * @return A gearbox of Kraken X44 FOC enabled motors. + */ + public static DCMotor getKrakenX44Foc(int numMotors) { + // From https://motors.ctr-electronics.com/dyno/dynometer-testing/ + return new DCMotor( + 12, 5.01, 329, 2, Units.rotationsPerMinuteToRadiansPerSecond(7368), numMotors); + } + + /** + * Return a gearbox of Minion brushless motors. + * + * @param numMotors Number of motors in the gearbox. + * @return A gearbox of Minion motors. + */ + public static DCMotor getMinion(int numMotors) { + // From https://motors.ctr-electronics.com/dyno/dynometer-testing/ + return new DCMotor( + 12, 3.17, 211, 2, Units.rotationsPerMinuteToRadiansPerSecond(7704), numMotors); + } + /** * Return a gearbox of Neo Vortex brushless motors. * diff --git a/wpimath/src/main/native/include/frc/system/plant/DCMotor.h b/wpimath/src/main/native/include/frc/system/plant/DCMotor.h index 90dc8299ea..145cf02bfd 100644 --- a/wpimath/src/main/native/include/frc/system/plant/DCMotor.h +++ b/wpimath/src/main/native/include/frc/system/plant/DCMotor.h @@ -247,6 +247,31 @@ class WPILIB_DLLEXPORT DCMotor { return DCMotor(12_V, 9.37_Nm, 483_A, 2_A, 5800_rpm, numMotors); } + /** + * Return a gearbox of Kraken X44 brushless motors. + */ + static constexpr DCMotor KrakenX44(int numMotors = 1) { + // From https://motors.ctr-electronics.com/dyno/dynometer-testing/ + return DCMotor(12_V, 4.11_Nm, 279_A, 2_A, 7758_rpm, numMotors); + } + + /** + * Return a gearbox of Kraken X44 brushless motors with FOC (Field-Oriented + * Control) enabled. + */ + static constexpr DCMotor KrakenX44FOC(int numMotors = 1) { + // From https://motors.ctr-electronics.com/dyno/dynometer-testing/ + return DCMotor(12_V, 5.01_Nm, 329_A, 2_A, 7368_rpm, numMotors); + } + + /** + * Return a gearbox of Minion brushless motors. + */ + static constexpr DCMotor Minion(int numMotors = 1) { + // From https://motors.ctr-electronics.com/dyno/dynometer-testing/ + return DCMotor(12_V, 3.17_Nm, 211_A, 2_A, 7704_rpm, numMotors); + } + /** * Return a gearbox of Neo Vortex brushless motors. */ From e45aadc8518ee4e017c308b12dae6f35528563be Mon Sep 17 00:00:00 2001 From: Jade Date: Sun, 2 Nov 2025 00:19:52 +0800 Subject: [PATCH 10/10] [sysid] Remove Phoenix5 CANcoder preset (#8316) Signed-off-by: Jade Turner --- sysid/src/main/native/include/sysid/view/Analyzer.h | 1 - 1 file changed, 1 deletion(-) diff --git a/sysid/src/main/native/include/sysid/view/Analyzer.h b/sysid/src/main/native/include/sysid/view/Analyzer.h index b856510621..47466b9fc3 100644 --- a/sysid/src/main/native/include/sysid/view/Analyzer.h +++ b/sysid/src/main/native/include/sysid/view/Analyzer.h @@ -55,7 +55,6 @@ class Analyzer : public glass::View { */ static constexpr const char* kPresetNames[] = {"Default", "WPILib", - "CTRE Phoenix 5 CANcoder", "CTRE Phoenix 5", "CTRE Phoenix 6", "REV Brushless Encoder Port",