From 7f6ba54b683d3b1a5fba36b200cd156205bd1aa8 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Mon, 8 Jul 2024 11:23:36 -0700 Subject: [PATCH 01/20] [wpimath] Report error when x and y components of Rotation2d are both zero (#6767) Fixes #6766. --- .../java/edu/wpi/first/math/geometry/Rotation2d.java | 3 +++ .../main/native/include/frc/geometry/Rotation2d.inc | 10 ++++++++++ 2 files changed, 13 insertions(+) diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java index 83366e576e4..cbcc3b91555 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java @@ -10,6 +10,7 @@ import com.fasterxml.jackson.annotation.JsonCreator; import com.fasterxml.jackson.annotation.JsonIgnoreProperties; import com.fasterxml.jackson.annotation.JsonProperty; +import edu.wpi.first.math.MathSharedStore; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.proto.Rotation2dProto; import edu.wpi.first.math.geometry.struct.Rotation2dStruct; @@ -118,6 +119,8 @@ public Rotation2d(double x, double y) { } else { m_sin = 0.0; m_cos = 1.0; + MathSharedStore.reportError( + "x and y components of Rotation2d are zero\n", Thread.currentThread().getStackTrace()); } m_value = Math.atan2(m_sin, m_cos); } diff --git a/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc b/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc index 104b66b1605..740aaf0090d 100644 --- a/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc +++ b/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc @@ -4,10 +4,15 @@ #pragma once +#include +#include + #include +#include #include "frc/geometry/Rotation2d.h" #include "units/angle.h" +#include "wpimath/MathShared.h" namespace frc { @@ -24,6 +29,11 @@ constexpr Rotation2d::Rotation2d(double x, double y) { } else { m_sin = 0.0; m_cos = 1.0; + if (!std::is_constant_evaluated()) { + wpi::math::MathSharedStore::ReportError( + "x and y components of Rotation2d are zero\n{}", + wpi::GetStackTrace(1)); + } } m_value = units::radian_t{gcem::atan2(m_sin, m_cos)}; } From dc276b651bb5079415d10e6def9d7eb6fb4b17ba Mon Sep 17 00:00:00 2001 From: Jade Date: Tue, 9 Jul 2024 09:25:42 +0800 Subject: [PATCH 02/20] [wpimath] Add reset methods to Odometry (#6702) --- .../wpi/first/math/kinematics/Odometry.java | 32 ++++++++++++++++++ .../native/include/frc/kinematics/Odometry.h | 33 +++++++++++++++++++ 2 files changed, 65 insertions(+) diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java index 0b4dab7a950..66ce592957d 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java @@ -6,6 +6,7 @@ import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Translation2d; /** * Class for odometry. Robot code should not use this directly- Instead, use the particular type for @@ -63,6 +64,37 @@ public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d poseMet m_previousWheelPositions = m_kinematics.copy(wheelPositions); } + /** + * Resets the pose. + * + * @param poseMeters The pose to reset to. + */ + public void resetPose(Pose2d poseMeters) { + m_gyroOffset = m_gyroOffset.plus(poseMeters.getRotation().minus(m_poseMeters.getRotation())); + m_poseMeters = poseMeters; + m_previousAngle = m_poseMeters.getRotation(); + } + + /** + * Resets the translation of the pose. + * + * @param translation The translation to reset to. + */ + public void resetTranslation(Translation2d translation) { + m_poseMeters = new Pose2d(translation, m_poseMeters.getRotation()); + } + + /** + * Resets the rotation of the pose. + * + * @param rotation The rotation to reset to. + */ + public void resetRotation(Rotation2d rotation) { + m_gyroOffset = m_gyroOffset.plus(rotation.minus(m_poseMeters.getRotation())); + m_poseMeters = new Pose2d(m_poseMeters.getTranslation(), rotation); + m_previousAngle = m_poseMeters.getRotation(); + } + /** * Returns the position of the robot on the field. * diff --git a/wpimath/src/main/native/include/frc/kinematics/Odometry.h b/wpimath/src/main/native/include/frc/kinematics/Odometry.h index 53066c7041a..c0daea0e3e0 100644 --- a/wpimath/src/main/native/include/frc/kinematics/Odometry.h +++ b/wpimath/src/main/native/include/frc/kinematics/Odometry.h @@ -7,6 +7,8 @@ #include #include "frc/geometry/Pose2d.h" +#include "frc/geometry/Rotation2d.h" +#include "frc/geometry/Translation2d.h" #include "frc/kinematics/Kinematics.h" #include "frc/kinematics/WheelPositions.h" @@ -58,6 +60,37 @@ class WPILIB_DLLEXPORT Odometry { m_previousWheelPositions = wheelPositions; } + /** + * Resets the pose. + * + * @param pose The pose to reset to. + */ + void ResetPose(const Pose2d& pose) { + m_gyroOffset = m_gyroOffset + (pose.Rotation() - m_pose.Rotation()); + m_pose = pose; + m_previousAngle = pose.Rotation(); + } + + /** + * Resets the translation of the pose. + * + * @param translation The translation to reset to. + */ + void ResetTranslation(const Translation2d& translation) { + m_pose = Pose2d{translation, m_pose.Rotation()}; + } + + /** + * Resets the rotation of the pose. + * + * @param rotation The rotation to reset to. + */ + void ResetRotation(const Rotation2d& rotation) { + m_gyroOffset = m_gyroOffset + (rotation - m_pose.Rotation()); + m_pose = Pose2d{m_pose.Translation(), rotation}; + m_previousAngle = rotation; + } + /** * Returns the position of the robot on the field. * @return The pose of the robot. From cc02a948a0f1a23a758e7437c07bb7682a724cce Mon Sep 17 00:00:00 2001 From: Jade Date: Tue, 9 Jul 2024 09:26:08 +0800 Subject: [PATCH 03/20] [wpimath] Add Reset methods to PoseEstimator (#6751) --- .../first/math/estimator/PoseEstimator.java | 31 +++++++++++++++++++ .../include/frc/estimator/PoseEstimator.h | 22 +++++++++++++ .../include/frc/estimator/PoseEstimator.inc | 23 ++++++++++++++ 3 files changed, 76 insertions(+) diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java index 5f17c83fd7f..2674e2ceaed 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java @@ -11,6 +11,7 @@ import edu.wpi.first.math.VecBuilder; 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.geometry.Twist2d; import edu.wpi.first.math.interpolation.TimeInterpolatableBuffer; import edu.wpi.first.math.kinematics.Kinematics; @@ -125,6 +126,36 @@ public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d poseMet m_poseEstimate = m_odometry.getPoseMeters(); } + /** + * Resets the robot's pose. + * + * @param pose The pose to reset to. + */ + public void resetPose(Pose2d pose) { + m_odometry.resetPose(pose); + m_odometryPoseBuffer.clear(); + } + + /** + * Resets the robot's translation. + * + * @param translation The pose to translation to. + */ + public void resetTranslation(Translation2d translation) { + m_odometry.resetTranslation(translation); + m_odometryPoseBuffer.clear(); + } + + /** + * Resets the robot's rotation. + * + * @param rotation The rotation to reset to. + */ + public void resetRotation(Rotation2d rotation) { + m_odometry.resetRotation(rotation); + m_odometryPoseBuffer.clear(); + } + /** * Gets the estimated robot pose. * diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h index cd0600f698b..da9f4f3ee68 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h @@ -15,6 +15,7 @@ #include "frc/geometry/Pose2d.h" #include "frc/geometry/Rotation2d.h" +#include "frc/geometry/Translation2d.h" #include "frc/interpolation/TimeInterpolatableBuffer.h" #include "frc/kinematics/Kinematics.h" #include "frc/kinematics/Odometry.h" @@ -87,6 +88,27 @@ class WPILIB_DLLEXPORT PoseEstimator { void ResetPosition(const Rotation2d& gyroAngle, const WheelPositions& wheelPositions, const Pose2d& pose); + /** + * Resets the robot's pose. + * + * @param pose The pose to reset to. + */ + void ResetPose(const Pose2d& pose); + + /** + * Resets the robot's translation. + * + * @param translation The pose to translation to. + */ + void ResetTranslation(const Translation2d& translation); + + /** + * Resets the robot's rotation. + * + * @param rotation The rotation to reset to. + */ + void ResetRotation(const Rotation2d& rotation); + /** * Gets the estimated robot pose. * diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc index f8bddca52d0..cb39dd26053 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc @@ -5,6 +5,9 @@ #pragma once #include "frc/estimator/PoseEstimator.h" +#include "frc/geometry/Pose2d.h" +#include "frc/geometry/Translation2d.h" +#include "frc/kinematics/WheelPositions.h" namespace frc { @@ -53,6 +56,26 @@ void PoseEstimator::ResetPosition( m_poseEstimate = m_odometry.GetPose(); } +template +void PoseEstimator::ResetPose(const Pose2d& pose) { + m_odometry.ResetPose(pose); + m_odometryPoseBuffer.Clear(); +} + +template +void PoseEstimator::ResetTranslation( + const Translation2d& translation) { + m_odometry.ResetTranslation(translation); + m_odometryPoseBuffer.Clear(); +} + +template +void PoseEstimator::ResetRotation( + const Rotation2d& rotation) { + m_odometry.ResetTranslation(rotation); + m_odometryPoseBuffer.Clear(); +} + template Pose2d PoseEstimator::GetEstimatedPosition() const { From c62863cf749ebff054e66e965e82e996b17e7773 Mon Sep 17 00:00:00 2001 From: Jade Date: Wed, 10 Jul 2024 00:25:31 +0800 Subject: [PATCH 04/20] [build] Fix CMake build for wpilibNewCommands (#6815) --- wpilibNewCommands/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/wpilibNewCommands/CMakeLists.txt b/wpilibNewCommands/CMakeLists.txt index 5b82b2f5ff6..18495fbd99c 100644 --- a/wpilibNewCommands/CMakeLists.txt +++ b/wpilibNewCommands/CMakeLists.txt @@ -9,12 +9,14 @@ if(WITH_JAVA) include(UseJava) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java src/generated/main/java/*.java) + file(GLOB JACKSON_JARS "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/jackson/*.jar") add_jar( wpilibNewCommands_jar ${JAVA_SOURCES} INCLUDE_JARS hal_jar ntcore_jar + ${JACKSON_JARS} cscore_jar cameraserver_jar wpimath_jar From 27a2e02b52c349d48a6c798d7cd4611d3d6200c8 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Wed, 10 Jul 2024 06:39:30 -0700 Subject: [PATCH 05/20] [upstream_utils] Upgrade Sleipnir to avoid pool allocator crash on Windows (#6821) --- upstream_utils/update_sleipnir.py | 4 ++-- .../include/sleipnir/autodiff/Expression.hpp | 24 +++++++++++++++---- 2 files changed, 21 insertions(+), 7 deletions(-) diff --git a/upstream_utils/update_sleipnir.py b/upstream_utils/update_sleipnir.py index de152f6e4fe..4b783c82bab 100755 --- a/upstream_utils/update_sleipnir.py +++ b/upstream_utils/update_sleipnir.py @@ -15,8 +15,8 @@ def main(): upstream_root = clone_repo( "https://github.com/SleipnirGroup/Sleipnir", - # main on 2024-07-05 - "b90f89d343379dd8dc88f22e0462eb7b59006b2c", + # main on 2024-07-09 + "b6ffa2d4fdb99cab1bf79491f715a6a9a86633b5", shallow=False, ) wpilib_root = get_repo_root() diff --git a/wpimath/src/main/native/thirdparty/sleipnir/include/sleipnir/autodiff/Expression.hpp b/wpimath/src/main/native/thirdparty/sleipnir/include/sleipnir/autodiff/Expression.hpp index 2be666e7c87..bdbeb473022 100644 --- a/wpimath/src/main/native/thirdparty/sleipnir/include/sleipnir/autodiff/Expression.hpp +++ b/wpimath/src/main/native/thirdparty/sleipnir/include/sleipnir/autodiff/Expression.hpp @@ -20,6 +20,14 @@ namespace sleipnir::detail { +// The global pool allocator uses a thread-local static pool resource, which +// isn't guaranteed to be initialized properly across DLL boundaries on Windows +#ifdef _WIN32 +inline constexpr bool kUsePoolAllocator = false; +#else +inline constexpr bool kUsePoolAllocator = true; +#endif + struct SLEIPNIR_DLLEXPORT Expression; inline void IntrusiveSharedPtrIncRefCount(Expression* expr); @@ -38,8 +46,12 @@ using ExpressionPtr = IntrusiveSharedPtr; */ template static ExpressionPtr MakeExpressionPtr(Args&&... args) { - return AllocateIntrusiveShared(GlobalPoolAllocator(), - std::forward(args)...); + if constexpr (kUsePoolAllocator) { + return AllocateIntrusiveShared( + GlobalPoolAllocator(), std::forward(args)...); + } else { + return MakeIntrusiveShared(std::forward(args)...); + } } /** @@ -437,9 +449,11 @@ inline void IntrusiveSharedPtrDecRefCount(Expression* expr) { // Not calling the destructor here is safe because it only decrements // refcounts, which was already done above. - auto alloc = GlobalPoolAllocator(); - std::allocator_traits::deallocate(alloc, elem, - sizeof(Expression)); + if constexpr (kUsePoolAllocator) { + auto alloc = GlobalPoolAllocator(); + std::allocator_traits::deallocate(alloc, elem, + sizeof(Expression)); + } } } } From bf75c03218a72987fae1a6bbd69b65bca83496dd Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Thu, 11 Jul 2024 18:01:05 -0400 Subject: [PATCH 06/20] [build] Clean up CMake files (#6802) Explicitly list required components when using FindJava and FindJNI Consolidate find_package calls for Java, JNI, and OpenCV into the root CMakeLists.txt file Remove references to main_lib_dest Install missing generated headers Flatten some if statements Use LinkMacOSGUI macro instead of hand rolling it Stop installing OpenCV libraries and an extra ntcorejni library; OpenCV JAR will still be installed to make it easy to use Only print platform version on Windows Prevent GUI modules from being built when wpimath is off, which would otherwise cause a build failure Simplify build configuration checks Clean up fieldImages JAR creation Place built JARs in the same subdir as installed JARs Remove unnecessary JAR includes Remove extra directories in target_include_directories Improve CMake docs --- CMakeLists.txt | 103 ++++----------------------- README-CMAKE.md | 11 ++- apriltag/CMakeLists.txt | 15 ++-- cameraserver/CMakeLists.txt | 9 +-- cmake/modules/OptionValidation.cmake | 29 ++++++++ cscore/CMakeLists.txt | 75 ++++--------------- fieldImages/CMakeLists.txt | 9 +-- hal/CMakeLists.txt | 5 +- imgui/CMakeLists.txt | 13 ++-- ntcore/CMakeLists.txt | 13 +--- romiVendordep/CMakeLists.txt | 6 +- simulation/halsim_xrp/CMakeLists.txt | 2 +- wpigui/CMakeLists.txt | 12 ++-- wpilibNewCommands/CMakeLists.txt | 8 ++- wpilibc/CMakeLists.txt | 2 +- wpilibj/CMakeLists.txt | 5 +- wpimath/CMakeLists.txt | 9 +-- wpinet/CMakeLists.txt | 7 +- wpiunits/CMakeLists.txt | 8 ++- wpiutil/CMakeLists.txt | 38 +++------- xrpVendordep/CMakeLists.txt | 6 +- 21 files changed, 132 insertions(+), 253 deletions(-) create mode 100644 cmake/modules/OptionValidation.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index ace8da81907..4010ef9eb27 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,6 +12,7 @@ endif() if("${CMAKE_HOST_SYSTEM_NAME}" STREQUAL "Windows") set(CMAKE_SYSTEM_VERSION 10.0.18362.0 CACHE STRING INTERNAL FORCE) set(CMAKE_VS_WINDOWS_TARGET_PLATFORM_VERSION 10.0.18362.0 CACHE STRING INTERNAL FORCE) + message(STATUS "Platform version: ${CMAKE_VS_WINDOWS_TARGET_PLATFORM_VERSION}") endif() cmake_minimum_required(VERSION 3.11) @@ -23,11 +24,10 @@ if(POLICY CMP0135) cmake_policy(SET CMP0135 NEW) endif() -message(STATUS "Platform version: ${CMAKE_VS_WINDOWS_TARGET_PLATFORM_VERSION}") - set(WPILIB_BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR}) include(CPack) +include(OptionValidation) set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS TRUE) set_property(GLOBAL PROPERTY USE_FOLDERS ON) @@ -35,7 +35,6 @@ set_property(GLOBAL PROPERTY USE_FOLDERS ON) set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${WPILIB_BINARY_DIR}/lib) set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${WPILIB_BINARY_DIR}/lib) set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${WPILIB_BINARY_DIR}/bin) -set(CMAKE_JAVA_TARGET_OUTPUT_DIR ${WPILIB_BINARY_DIR}/jar) # use, i.e. don't skip the full RPATH for the build tree set(CMAKE_SKIP_BUILD_RPATH FALSE) @@ -87,28 +86,6 @@ if(NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "" FORCE) endif() -if(WITH_JAVA AND NOT BUILD_SHARED_LIBS) - message( - FATAL_ERROR - " -FATAL: Cannot build static libs with Java enabled. - Static libs requires both BUILD_SHARED_LIBS=OFF and - WITH_JAVA=OFF -" - ) -endif() - -if(WITH_SIMULATION_MODULES AND NOT BUILD_SHARED_LIBS) - message( - FATAL_ERROR - " -FATAL: Cannot build static libs with simulation modules enabled. - Static libs requires both BUILD_SHARED_LIBS=OFF and - WITH_SIMULATION_MODULES=OFF -" - ) -endif() - if(NOT WITH_JAVA OR NOT WITH_CSCORE) if(NOT "${OPENCV_JAVA_INSTALL_DIR}" STREQUAL "") message( @@ -121,81 +98,24 @@ It will be ignored. endif() endif() -if(NOT WITH_WPILIB AND WITH_SIMULATION_MODULES) - message( - FATAL_ERROR - " -FATAL: Cannot build simulation modules with wpilib disabled. - Enable wpilib by setting WITH_WPILIB=ON -" - ) -endif() - -if(NOT WITH_NTCORE AND WITH_CSCORE) - message( - FATAL_ERROR - " -FATAL: Cannot build cameraserver without ntcore. - Enable ntcore by setting WITH_NTCORE=ON -" - ) -endif() +wpilib_config(OPTIONS WITH_JAVA REQUIRES BUILD_SHARED_LIBS) -if(NOT WITH_NTCORE AND WITH_GUI) - message( - FATAL_ERROR - " -FATAL: Cannot build GUI modules without ntcore. - Enable ntcore by setting WITH_NTCORE=ON -" - ) -endif() +wpilib_config(OPTIONS WITH_SIMULATION_MODULES REQUIRES BUILD_SHARED_LIBS WITH_WPILIB WITH_NTCORE) -if(NOT WITH_NTCORE AND WITH_SIMULATION_MODULES) - message( - FATAL_ERROR - " -FATAL: Cannot build simulation modules without ntcore. - Enable ntcore by setting WITH_NTCORE=ON -" - ) -endif() +wpilib_config(OPTIONS WITH_CSCORE REQUIRES WITH_NTCORE) -if(NOT WITH_NTCORE AND WITH_WPILIB) - message( - FATAL_ERROR - " -FATAL: Cannot build wpilib without ntcore. - Enable ntcore by setting WITH_NTCORE=ON -" - ) -endif() +wpilib_config(OPTIONS WITH_GUI REQUIRES WITH_NTCORE WITH_WPIMATH) -if(NOT WITH_WPIMATH AND WITH_WPILIB) - message( - FATAL_ERROR - " -FATAL: Cannot build wpilib without wpimath. - Enable wpimath by setting WITH_WPIMATH=ON -" - ) -endif() +wpilib_config(OPTIONS WITH_WPILIB REQUIRES WITH_NTCORE WITH_WPIMATH) -if(NOT WITH_WPIUNITS AND WITH_WPIMATH AND WITH_JAVA) - message( - FATAL_ERROR - " -FATAL: Cannot build Java wpimath without wpiunits. - Enable wpiunits by setting WITH_WPIUNITS=ON or disable the Java build by setting WITH_JAVA=OFF -" - ) -endif() +wpilib_config(OPTIONS WITH_WPIMATH WITH_JAVA REQUIRES WITH_WPIUNITS) set(include_dest include) set(java_lib_dest java) -set(jni_lib_dest jni) -if(WITH_JAVA) +if(WITH_JAVA OR WITH_JAVA_SOURCE) set(CMAKE_JAVA_COMPILE_FLAGS "-encoding" "UTF8" "-Xlint:unchecked") + find_package(Java REQUIRED COMPONENTS Development) + find_package(JNI REQUIRED COMPONENTS JVM) endif() find_package(LIBSSH 0.7.1) @@ -382,6 +302,7 @@ endif() if(WITH_CSCORE) set(CAMERASERVER_DEP_REPLACE "find_dependency(cameraserver)") set(CSCORE_DEP_REPLACE "find_dependency(cscore)") + find_package(OpenCV REQUIRED) add_subdirectory(cscore) add_subdirectory(cameraserver) endif() diff --git a/README-CMAKE.md b/README-CMAKE.md index 7742900f9e6..e52d77ec2ef 100644 --- a/README-CMAKE.md +++ b/README-CMAKE.md @@ -108,6 +108,12 @@ After build, the easiest way to use the libraries is to install them. Run the fo sudo cmake --build . --target install ``` +## Preparing to use the installed libraries + +On Windows, make sure the directories for the libraries you built are on PATH. For wpilib, the default install location is `C:\Program Files (x86)\allwpilib`. If you built other libraries like OpenCV and protobuf from source, install them, and add the install directories to PATH. This ensures CMake can locate the libraries. + +You will also want to add the directories where the DLLs are located (usually the `bin` subdirectory of the install directory) to PATH so they can be loaded by your program. If you are using OpenCV and Java, the `opencv_java` DLL is located in either the `lib` subdirectory if you built but didn't install OpenCV, or the `java` subdirectory if you did install OpenCV. + ## Using the installed libraries for C++. Using the libraries from C++ is the easiest way to use the built libraries. @@ -134,12 +140,11 @@ cmake /path/to/folder/containing/CMakeLists After that, run `cmake --build .`. That will create your executable. Then you should be able to run `./my_vision_app` to run your application. - ## Using the installed libraries for Java -Using the built JARs is move involved than using the C++ libraries, but mostly consists of adding the correct directories to PATH. +Using the built JARs is more involved than using the C++ libraries, but the additional work involves providing the paths to various libraries and JARs when needed. -Add the directory where the JARs are located (e.g, `/usr/local/java`) to PATH. If you are on Windows, you also need to add the `lib`, `bin`, and `share` directories to PATH. Then, create a new folder to contain your project. Add the following code below to a `CMakeLists.txt` file in that directory. +Create a new folder to contain your project. Add the following code below to a `CMakeLists.txt` file in that directory. ```cmake cmake_minimum_required(VERSION 3.11) diff --git a/apriltag/CMakeLists.txt b/apriltag/CMakeLists.txt index e6b9aa6f97f..28a2751d577 100644 --- a/apriltag/CMakeLists.txt +++ b/apriltag/CMakeLists.txt @@ -27,8 +27,6 @@ set(APRILTAGLIB_SRCS file(GLOB apriltag_jni_src src/main/native/cpp/jni/AprilTagJNI.cpp) if(WITH_JAVA) - find_package(Java REQUIRED) - find_package(JNI REQUIRED) include(UseJava) set(CMAKE_JNI_TARGET true) @@ -47,8 +45,6 @@ if(WITH_JAVA) NO_DEFAULT_PATH ) - set(CMAKE_JAVA_INCLUDE_PATH apriltag.jar ${EJML_JARS} ${JACKSON_JARS}) - file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java) file( GLOB_RECURSE JAVA_RESOURCES @@ -60,8 +56,15 @@ if(WITH_JAVA) SOURCES ${JAVA_SOURCES} RESOURCES NAMESPACE "edu/wpi/first/apriltag" ${JAVA_RESOURCES} - INCLUDE_JARS wpimath_jar wpiunits_jar ${EJML_JARS} wpiutil_jar ${OPENCV_JAR_FILE} + INCLUDE_JARS + wpimath_jar + wpiunits_jar + wpiutil_jar + ${EJML_JARS} + ${OPENCV_JAR_FILE} + ${JACKSON_JARS} OUTPUT_NAME apriltag + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} GENERATE_NATIVE_HEADERS apriltag_jni_headers ) set_property(TARGET apriltag_jar PROPERTY FOLDER "java") @@ -83,7 +86,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file(GLOB APRILTAG_SOURCES src/main/java/edu/wpi/first/apriltag/*.java) add_jar( @@ -94,6 +96,7 @@ if(WITH_JAVA_SOURCE) "edu/wpi/first/apriltag/jni" src/main/java/edu/wpi/first/apriltag/jni/AprilTagJNI.java OUTPUT_NAME apriltag-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(APRILTAG_SRC_JAR_FILE TARGET apriltag_src_jar PROPERTY JAR_FILE) diff --git a/cameraserver/CMakeLists.txt b/cameraserver/CMakeLists.txt index 1270c383db5..2ea645470e2 100644 --- a/cameraserver/CMakeLists.txt +++ b/cameraserver/CMakeLists.txt @@ -3,15 +3,11 @@ project(cameraserver) include(CompileWarnings) include(AddTest) -find_package(OpenCV REQUIRED) - # Java bindings if(WITH_JAVA) - find_package(Java REQUIRED) include(UseJava) - #find java files, copy them locally - + #find JAR file, copy it locally set(OPENCV_JAVA_INSTALL_DIR ${OpenCV_INSTALL_PATH}/share/java/opencv4) find_file( @@ -32,6 +28,7 @@ if(WITH_JAVA) ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar cscore_jar ntcore_jar ${OPENCV_JAR_FILE} OUTPUT_NAME cameraserver + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) set_property(TARGET cameraserver_jar PROPERTY FOLDER "java") @@ -44,7 +41,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file(GLOB CAMERASERVER_SOURCES src/main/java/edu/wpi/first/cameraserver/*.java) file(GLOB VISION_SOURCES src/main/java/edu/wpi/first/vision/*.java) @@ -54,6 +50,7 @@ if(WITH_JAVA_SOURCE) NAMESPACE "edu/wpi/first/cameraserver" ${CAMERASERVER_SOURCES} NAMESPACE "edu/wpi/first/vision" ${VISION_SOURCES} OUTPUT_NAME cameraserver-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(CAMERASERVER_SRC_JAR_FILE TARGET cameraserver_src_jar PROPERTY JAR_FILE) diff --git a/cmake/modules/OptionValidation.cmake b/cmake/modules/OptionValidation.cmake new file mode 100644 index 00000000000..4460ac44159 --- /dev/null +++ b/cmake/modules/OptionValidation.cmake @@ -0,0 +1,29 @@ +function(wpilib_config) + cmake_parse_arguments(config "" "" "OPTIONS;REQUIRES" ${ARGN}) + foreach(opt ${config_OPTIONS}) + if(NOT ${opt}) + return() + endif() + endforeach() + foreach(required_opt ${config_REQUIRES}) + if(NOT ${required_opt}) + list(JOIN config_OPTIONS " and " options_list) + list(LENGTH config_OPTIONS option_len) + if(option_len GREATER 1) + set(requires require) + set(option_msg "one of the listed options") + else() + set(requires requires) + set(option_msg ${options_list}) + endif() + + message( + FATAL_ERROR + " +FATAL: ${options_list} ${requires} ${required_opt}. + Either enable ${required_opt} or disable ${option_msg}. +" + ) + endif() + endforeach() +endfunction() diff --git a/cscore/CMakeLists.txt b/cscore/CMakeLists.txt index e4f4315acc5..24b605e9026 100644 --- a/cscore/CMakeLists.txt +++ b/cscore/CMakeLists.txt @@ -5,8 +5,6 @@ include(CompileWarnings) include(AddTest) include(LinkMacOSGUI) -find_package(OpenCV REQUIRED) - file(GLOB cscore_native_src src/main/native/cpp/*.cpp) file(GLOB cscore_linux_src src/main/native/linux/*.cpp) file(GLOB cscore_osx_src src/main/native/osx/*.cpp) @@ -16,23 +14,21 @@ file(GLOB cscore_windows_src src/main/native/windows/*.cpp) add_library(cscore ${cscore_native_src}) set_target_properties(cscore PROPERTIES DEBUG_POSTFIX "d") -if(NOT MSVC) - if(APPLE) - target_sources(cscore PRIVATE ${cscore_osx_src} ${cscore_osx_objc_src}) - target_compile_options(cscore PRIVATE "-fobjc-arc") - set_target_properties( - cscore - PROPERTIES - LINK_FLAGS - "-framework CoreFoundation -framework AVFoundation -framework Foundation -framework CoreMedia -framework CoreVideo" - ) - else() - target_sources(cscore PRIVATE ${cscore_linux_src}) - endif() -else() +if(APPLE) + target_sources(cscore PRIVATE ${cscore_osx_src} ${cscore_osx_objc_src}) + target_compile_options(cscore PRIVATE "-fobjc-arc") + set_target_properties( + cscore + PROPERTIES + LINK_FLAGS + "-framework CoreFoundation -framework AVFoundation -framework Foundation -framework CoreMedia -framework CoreVideo" + ) +elseif(MSVC) target_sources(cscore PRIVATE ${cscore_windows_src}) target_compile_definitions(cscore PUBLIC -DNOMINMAX) target_compile_definitions(cscore PRIVATE -D_CRT_SECURE_NO_WARNINGS) +else() + target_sources(cscore PRIVATE ${cscore_linux_src}) endif() target_include_directories( @@ -81,12 +77,9 @@ endforeach() # Java bindings if(WITH_JAVA) - find_package(Java REQUIRED) - find_package(JNI REQUIRED) include(UseJava) - #find java files, copy them locally - + #find JAR file, copy it locally if("${OPENCV_JAVA_INSTALL_DIR}" STREQUAL "") set(OPENCV_JAVA_INSTALL_DIR ${OpenCV_INSTALL_PATH}/share/java/opencv4) endif() @@ -101,24 +94,6 @@ if(WITH_JAVA) ${OpenCV_INSTALL_PATH}/share/OpenCV/java NO_DEFAULT_PATH ) - find_file( - OPENCV_JNI_FILE - NAMES - libopencv_java${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.so - libopencv_java${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.dylib - opencv_java${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.dll - PATHS - ${OPENCV_JAVA_INSTALL_DIR} - ${OpenCV_INSTALL_PATH}/bin - ${OpenCV_INSTALL_PATH}/bin/Release - ${OpenCV_INSTALL_PATH}/bin/Debug - ${OpenCV_INSTALL_PATH}/lib - ${OpenCV_INSTALL_PATH}/lib/Release - ${OpenCV_INSTALL_PATH}/lib/Debug - ${OpenCV_INSTALL_PATH}/lib/jni - ${OpenCV_INSTALL_PATH}/share/java/opencv4 - NO_DEFAULT_PATH - ) file(GLOB cscore_jni_src src/main/native/cpp/jni/CameraServerJNI.cpp) @@ -130,6 +105,7 @@ if(WITH_JAVA) ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar ${OPENCV_JAR_FILE} OUTPUT_NAME cscore + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} GENERATE_NATIVE_HEADERS cscore_jni_headers ) set_property(TARGET cscore_jar PROPERTY FOLDER "java") @@ -138,27 +114,6 @@ if(WITH_JAVA) install_jar_exports(TARGETS cscore_jar FILE cscore_jar.cmake DESTINATION share/cscore) install(FILES ${OPENCV_JAR_FILE} DESTINATION "${java_lib_dest}") - if(MSVC) - install(FILES ${OPENCV_JNI_FILE} DESTINATION "${jni_lib_dest}") - - foreach(cvFile ${OpenCV_LIBS}) - find_file( - ${cvFile}Loc - NAMES - ${cvFile}${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.dll - ${cvFile}${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}d.dll - PATHS - ${OPENCV_JAVA_INSTALL_DIR} - ${OpenCV_INSTALL_PATH}/bin - ${OpenCV_INSTALL_PATH}/bin/Release - ${OpenCV_INSTALL_PATH}/bin/Debug - ${OpenCV_INSTALL_PATH}/lib - NO_DEFAULT_PATH - ) - install(FILES ${${cvFile}Loc} DESTINATION "${jni_lib_dest}") - endforeach() - endif() - add_library(cscorejni ${cscore_jni_src}) wpilib_target_warnings(cscorejni) target_link_libraries(cscorejni PUBLIC cscore wpiutil ${OpenCV_LIBS}) @@ -173,7 +128,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file(GLOB CSCORE_SOURCES src/main/java/edu/wpi/first/cscore/*.java) file(GLOB CSCORE_RAW_SOURCES src/main/java/edu/wpi/first/cscore/raw/*.java) @@ -183,6 +137,7 @@ if(WITH_JAVA_SOURCE) NAMESPACE "edu/wpi/first/cscore" ${CSCORE_SOURCES} NAMESPACE "edu/wpi/first/cscore/raw" ${CSCORE_RAW_SOURCES} OUTPUT_NAME cscore-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(CSCORE_SRC_JAR_FILE TARGET cscore_src_jar PROPERTY JAR_FILE) diff --git a/fieldImages/CMakeLists.txt b/fieldImages/CMakeLists.txt index d5607c99e18..315615b106a 100644 --- a/fieldImages/CMakeLists.txt +++ b/fieldImages/CMakeLists.txt @@ -4,11 +4,9 @@ include(CompileWarnings) include(GenResources) if(WITH_JAVA) - find_package(Java REQUIRED) include(UseJava) file(GLOB JACKSON_JARS "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/jackson/*.jar") - set(CMAKE_JAVA_INCLUDE_PATH fieldImages.jar ${JACKSON_JARS}) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java) file( @@ -23,13 +21,12 @@ if(WITH_JAVA) SOURCES ${JAVA_SOURCES} RESOURCES NAMESPACE "edu/wpi/first/fields" ${JAVA_RESOURCES} + INCLUDE_JARS ${JACKSON_JARS} + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} OUTPUT_NAME fieldImages ) - - get_property(FIELD_IMAGES_JAR_FILE TARGET field_images_jar PROPERTY JAR_FILE) - install(FILES ${FIELD_IMAGES_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET field_images_jar PROPERTY FOLDER "java") + install_jar(field_images_jar DESTINATION ${java_lib_dest}) endif() generate_resources( diff --git a/hal/CMakeLists.txt b/hal/CMakeLists.txt index 7070859ce15..31f640cec8a 100644 --- a/hal/CMakeLists.txt +++ b/hal/CMakeLists.txt @@ -43,8 +43,6 @@ install(EXPORT hal DESTINATION share/hal) # Java bindings if(WITH_JAVA) - find_package(Java REQUIRED) - find_package(JNI REQUIRED) include(UseJava) file(GLOB_RECURSE hal_shared_jni_src src/main/native/cpp/jni/*.cpp) @@ -57,6 +55,7 @@ if(WITH_JAVA) ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar OUTPUT_NAME wpiHal + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} GENERATE_NATIVE_HEADERS hal_jni_headers ) set_property(TARGET hal_jar PROPERTY FOLDER "java") @@ -80,7 +79,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file(GLOB HAL_SOURCES src/main/java/edu/wpi/first/hal/*.java src/generated/main/java/*.java) file(GLOB HAL_CAN_SOURCES src/main/java/edu/wpi/first/hal/can/*.java) @@ -97,6 +95,7 @@ if(WITH_JAVA_SOURCE) NAMESPACE "edu/wpi/first/hal/simulation" ${HAL_SIMULATION_SOURCES} NAMESPACE "edu/wpi/first/hal/util" ${HAL_UTIL_SOURCES} OUTPUT_NAME wpiHal-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(HAL_SRC_JAR_FILE TARGET hal_src_jar PROPERTY JAR_FILE) diff --git a/imgui/CMakeLists.txt b/imgui/CMakeLists.txt index b4810e9ce01..04a6a3aeb92 100644 --- a/imgui/CMakeLists.txt +++ b/imgui/CMakeLists.txt @@ -1,4 +1,5 @@ include(FetchContent) +include(LinkMacOSGUI) fetchcontent_declare( glfw3 @@ -82,14 +83,12 @@ endif() target_compile_definitions(imgui PUBLIC IMGUI_IMPL_OPENGL_LOADER_GL3W) if(MSVC) target_sources(imgui PRIVATE ${imgui_SOURCE_DIR}/backends/imgui_impl_dx11.cpp) +elseif(APPLE) + target_compile_options(imgui PRIVATE -fobjc-arc) + wpilib_link_macos_gui(imgui) + target_sources(imgui PRIVATE ${imgui_SOURCE_DIR}/backends/imgui_impl_metal.mm) else() - if(APPLE) - target_compile_options(imgui PRIVATE -fobjc-arc) - set_target_properties(imgui PROPERTIES LINK_FLAGS "-framework Metal -framework QuartzCore") - target_sources(imgui PRIVATE ${imgui_SOURCE_DIR}/backends/imgui_impl_metal.mm) - else() - #target_sources(imgui PRIVATE ${imgui_SOURCE_DIR}/backends/imgui_impl_opengl3.cpp) - endif() + #target_sources(imgui PRIVATE ${imgui_SOURCE_DIR}/backends/imgui_impl_opengl3.cpp) endif() target_link_libraries(imgui PUBLIC glfw) target_include_directories( diff --git a/ntcore/CMakeLists.txt b/ntcore/CMakeLists.txt index bbf3790a7b4..101307886df 100644 --- a/ntcore/CMakeLists.txt +++ b/ntcore/CMakeLists.txt @@ -39,14 +39,10 @@ install(EXPORT ntcore DESTINATION share/ntcore) # Java bindings if(WITH_JAVA) - find_package(Java REQUIRED) - find_package(JNI REQUIRED) include(UseJava) file(GLOB QUICKBUF_JAR ${WPILIB_BINARY_DIR}/wpiutil/thirdparty/quickbuf/*.jar) - set(CMAKE_JAVA_INCLUDE_PATH wpimath.jar ${QUICKBUF_JAR}) - file(GLOB ntcore_jni_src src/main/native/cpp/jni/*.cpp src/generated/main/native/cpp/jni/*.cpp) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java src/generated/main/java/*.java) @@ -55,8 +51,9 @@ if(WITH_JAVA) add_jar( ntcore_jar ${JAVA_SOURCES} - INCLUDE_JARS wpiutil_jar + INCLUDE_JARS wpiutil_jar ${QUICKBUF_JAR} OUTPUT_NAME ntcore + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} GENERATE_NATIVE_HEADERS ntcore_jni_headers ) set_property(TARGET ntcore_jar PROPERTY FOLDER "java") @@ -70,10 +67,6 @@ if(WITH_JAVA) set_property(TARGET ntcorejni PROPERTY FOLDER "libraries") - if(MSVC) - install(TARGETS ntcorejni RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime) - endif() - target_link_libraries(ntcorejni PRIVATE ntcore_jni_headers) add_dependencies(ntcorejni ntcore_jar) @@ -82,7 +75,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file( GLOB NTCORE_SOURCES @@ -94,6 +86,7 @@ if(WITH_JAVA_SOURCE) RESOURCES NAMESPACE "edu/wpi/first/networktables" ${NTCORE_SOURCES} OUTPUT_NAME ntcore-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(NTCORE_SRC_JAR_FILE TARGET ntcore_src_jar PROPERTY JAR_FILE) diff --git a/romiVendordep/CMakeLists.txt b/romiVendordep/CMakeLists.txt index 960e7d112e8..cae07076089 100644 --- a/romiVendordep/CMakeLists.txt +++ b/romiVendordep/CMakeLists.txt @@ -5,7 +5,6 @@ include(CompileWarnings) include(AddTest) if(WITH_JAVA) - find_package(Java REQUIRED) include(UseJava) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java) @@ -22,6 +21,7 @@ if(WITH_JAVA) wpiutil_jar wpilibj_jar OUTPUT_NAME romiVendordep + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) set_property(TARGET romiVendordep_jar PROPERTY FOLDER "java") @@ -34,7 +34,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file(GLOB_RECURSE ROMIVENDORDEP_SOURCES src/main/java/*.java) add_jar( @@ -42,6 +41,7 @@ if(WITH_JAVA_SOURCE) RESOURCES NAMESPACE "edu/wpi/first/wpilibj/romi" ${ROMIVENDORDEP_SOURCES} OUTPUT_NAME romiVendordep-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(ROMIVENDORDEP_SRC_JAR_FILE TARGET romiVendordep_src_jar PROPERTY JAR_FILE) @@ -66,7 +66,7 @@ target_include_directories( $ ) -install(TARGETS romiVendordep EXPORT romivendordep DESTINATION "${main_lib_dest}") +install(TARGETS romiVendordep EXPORT romivendordep) export(TARGETS romiVendordep FILE romivendordep.cmake NAMESPACE romivendordep::) install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/romiVendordep") diff --git a/simulation/halsim_xrp/CMakeLists.txt b/simulation/halsim_xrp/CMakeLists.txt index f961f3b94d2..71f8c53ecfe 100644 --- a/simulation/halsim_xrp/CMakeLists.txt +++ b/simulation/halsim_xrp/CMakeLists.txt @@ -13,5 +13,5 @@ target_include_directories(halsim_xrp PRIVATE src/main/native/include) set_property(TARGET halsim_xrp PROPERTY FOLDER "libraries") -install(TARGETS halsim_xrp EXPORT halsim_xrp DESTINATION "${main_lib_dest}") +install(TARGETS halsim_xrp EXPORT halsim_xrp) export(TARGETS halsim_xrp FILE halsim_xrp.cmake NAMESPACE halsim_xrp::) diff --git a/wpigui/CMakeLists.txt b/wpigui/CMakeLists.txt index 221977728f4..04ffe3b2dcc 100644 --- a/wpigui/CMakeLists.txt +++ b/wpigui/CMakeLists.txt @@ -30,14 +30,12 @@ target_include_directories( if(MSVC) target_sources(wpigui PRIVATE ${wpigui_windows_src}) +elseif(APPLE) + target_compile_options(wpigui PRIVATE -fobjc-arc) + wpilib_link_macos_gui(wpigui) + target_sources(wpigui PRIVATE ${wpigui_mac_src}) else() - if(APPLE) - target_compile_options(wpigui PRIVATE -fobjc-arc) - set_target_properties(wpigui PROPERTIES LINK_FLAGS "-framework Metal -framework QuartzCore") - target_sources(wpigui PRIVATE ${wpigui_mac_src}) - else() - target_sources(wpigui PRIVATE ${wpigui_unix_src}) - endif() + target_sources(wpigui PRIVATE ${wpigui_unix_src}) endif() add_executable(wpiguidev src/dev/native/cpp/main.cpp) diff --git a/wpilibNewCommands/CMakeLists.txt b/wpilibNewCommands/CMakeLists.txt index 18495fbd99c..43292dfbe47 100644 --- a/wpilibNewCommands/CMakeLists.txt +++ b/wpilibNewCommands/CMakeLists.txt @@ -5,7 +5,6 @@ include(CompileWarnings) include(AddTest) if(WITH_JAVA) - find_package(Java REQUIRED) include(UseJava) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java src/generated/main/java/*.java) @@ -24,6 +23,7 @@ if(WITH_JAVA) wpiutil_jar wpilibj_jar OUTPUT_NAME wpilibNewCommands + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) set_property(TARGET wpilibNewCommands_jar PROPERTY FOLDER "java") @@ -36,7 +36,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file(GLOB WPILIBNEWCOMMANDS_SOURCES src/main/java/edu/wpi/first/wpilibj2/command/*.java) file( @@ -50,6 +49,7 @@ if(WITH_JAVA_SOURCE) NAMESPACE "edu/wpi/first/wpilibj2/command" ${WPILIBNEWCOMMANDS_SOURCES} NAMESPACE "edu/wpi/first/wpilibj2/command/button" ${WPILIBNEWCOMMANDS_BUTTON_SOURCES} OUTPUT_NAME wpilibNewCommands-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(WPILIBNEWCOMMANDS_SRC_JAR_FILE TARGET wpilibNewCommands_src_jar PROPERTY JAR_FILE) @@ -82,6 +82,10 @@ target_include_directories( install(TARGETS wpilibNewCommands EXPORT wpilibnewcommands) export(TARGETS wpilibNewCommands FILE wpilibnewcommands.cmake NAMESPACE wpilibnewcommands::) install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpilibNewCommands") +install( + DIRECTORY src/generated/main/native/include/ + DESTINATION "${include_dest}/wpilibNewCommands" +) configure_file( wpilibnewcommands-config.cmake.in diff --git a/wpilibc/CMakeLists.txt b/wpilibc/CMakeLists.txt index 186c9794b14..7046509e7ae 100644 --- a/wpilibc/CMakeLists.txt +++ b/wpilibc/CMakeLists.txt @@ -25,7 +25,6 @@ target_include_directories( wpilib_target_warnings(wpilibc) if(WITH_CSCORE) - find_package(OpenCV) target_link_libraries(wpilibc PUBLIC cameraserver cscore ${OpenCV_LIBS}) else() target_compile_definitions(wpilibc PRIVATE DYNAMIC_CAMERA_SERVER) @@ -43,6 +42,7 @@ set_property(TARGET wpilibc PROPERTY FOLDER "libraries") install(TARGETS wpilibc EXPORT wpilibc) export(TARGETS wpilibc FILE wpilibc.cmake NAMESPACE wpilibc::) install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpilibc") +install(DIRECTORY src/generated/main/native/include/ DESTINATION "${include_dest}/wpilibc") configure_file(wpilibc-config.cmake.in ${WPILIB_BINARY_DIR}/wpilibc-config.cmake) install(FILES ${WPILIB_BINARY_DIR}/wpilibc-config.cmake DESTINATION share/wpilibc) diff --git a/wpilibj/CMakeLists.txt b/wpilibj/CMakeLists.txt index e2a8fb331a7..6124368075f 100644 --- a/wpilibj/CMakeLists.txt +++ b/wpilibj/CMakeLists.txt @@ -2,8 +2,6 @@ project(wpilibj) # Java bindings if(WITH_JAVA) - find_package(OpenCV REQUIRED) - find_package(Java REQUIRED) include(UseJava) set(OPENCV_JAVA_INSTALL_DIR ${OpenCV_INSTALL_PATH}/share/java/opencv4) @@ -41,6 +39,7 @@ if(WITH_JAVA) wpiunits_jar wpiutil_jar OUTPUT_NAME wpilibj + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) set_property(TARGET wpilibj_jar PROPERTY FOLDER "java") @@ -51,7 +50,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file( GLOB WPILIBJ_SOURCES @@ -95,6 +93,7 @@ if(WITH_JAVA_SOURCE) NAMESPACE "edu/wpi/first/wpilibj/smartdashboard" ${WPILIBJ_SMARTDASHBOARD_SOURCES} NAMESPACE "edu/wpi/first/wpilibj/util" ${WPILIBJ_UTIL_SOURCES} OUTPUT_NAME wpilibj-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(WPILIBJ_SRC_JAR_FILE TARGET wpilibj_src_jar PROPERTY JAR_FILE) diff --git a/wpimath/CMakeLists.txt b/wpimath/CMakeLists.txt index f56558410af..80ed18d40cd 100644 --- a/wpimath/CMakeLists.txt +++ b/wpimath/CMakeLists.txt @@ -31,8 +31,6 @@ file( # Java bindings if(WITH_JAVA) - find_package(Java REQUIRED) - find_package(JNI REQUIRED) include(UseJava) if(NOT EXISTS "${WPILIB_BINARY_DIR}/wpimath/thirdparty/ejml/ejml-simple-0.43.1.jar") @@ -77,8 +75,6 @@ if(WITH_JAVA) file(GLOB JACKSON_JARS "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/jackson/*.jar") file(GLOB QUICKBUF_JAR ${WPILIB_BINARY_DIR}/wpiutil/thirdparty/quickbuf/*.jar) - set(CMAKE_JAVA_INCLUDE_PATH wpimath.jar ${EJML_JARS} ${JACKSON_JARS} ${QUICKBUF_JAR}) - set(CMAKE_JNI_TARGET true) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java src/generated/main/java/*.java) @@ -86,8 +82,9 @@ if(WITH_JAVA) add_jar( wpimath_jar ${JAVA_SOURCES} - INCLUDE_JARS ${EJML_JARS} wpiutil_jar wpiunits_jar + INCLUDE_JARS wpiutil_jar wpiunits_jar ${EJML_JARS} ${JACKSON_JARS} ${QUICKBUF_JAR} OUTPUT_NAME wpimath + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} GENERATE_NATIVE_HEADERS wpimath_jni_headers ) set_property(TARGET wpimath_jar PROPERTY FOLDER "java") @@ -109,7 +106,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file( GLOB WPIMATH_SOURCES @@ -150,6 +146,7 @@ if(WITH_JAVA_SOURCE) ${WPIMATH_TRAJECTORY_CONSTRAINT_SOURCES} NAMESPACE "edu/wpi/first/math/util" src/main/java/edu/wpi/first/math/util/Units.java OUTPUT_NAME wpimath-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(WPIMATH_SRC_JAR_FILE TARGET wpimath_src_jar PROPERTY JAR_FILE) diff --git a/wpinet/CMakeLists.txt b/wpinet/CMakeLists.txt index 7e189a87ab9..bddb4db83a9 100644 --- a/wpinet/CMakeLists.txt +++ b/wpinet/CMakeLists.txt @@ -9,8 +9,6 @@ file(GLOB wpinet_jni_src src/main/native/cpp/jni/WPINetJNI.cpp) # Java bindings if(WITH_JAVA) - find_package(Java REQUIRED) - find_package(JNI REQUIRED) include(UseJava) set(CMAKE_JNI_TARGET true) @@ -22,6 +20,7 @@ if(WITH_JAVA) ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar OUTPUT_NAME wpinet + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} GENERATE_NATIVE_HEADERS wpinet_jni_headers ) set_property(TARGET wpinet_jar PROPERTY FOLDER "java") @@ -43,7 +42,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file(GLOB WPINET_SOURCES src/main/java/edu/wpi/first/net/*.java) add_jar( @@ -51,6 +49,7 @@ if(WITH_JAVA_SOURCE) RESOURCES NAMESPACE "edu/wpi/first/net" ${WPINET_SOURCES} OUTPUT_NAME wpinet-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(WPINET_SRC_JAR_FILE TARGET wpinet_src_jar PROPERTY JAR_FILE) @@ -145,7 +144,6 @@ if(NOT USE_SYSTEM_LIBUV) wpinet PUBLIC $ - $ ) if(NOT MSVC) target_sources(wpinet PRIVATE ${uv_unix_src}) @@ -185,7 +183,6 @@ target_include_directories( wpinet PUBLIC $ - $ ) install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpinet") diff --git a/wpiunits/CMakeLists.txt b/wpiunits/CMakeLists.txt index 4f71da1b15e..3cba94bfd63 100644 --- a/wpiunits/CMakeLists.txt +++ b/wpiunits/CMakeLists.txt @@ -2,12 +2,16 @@ project(wpiunits) # Java bindings if(WITH_JAVA) - find_package(Java REQUIRED) include(UseJava) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java) - add_jar(wpiunits_jar ${JAVA_SOURCES} OUTPUT_NAME wpiunits) + add_jar( + wpiunits_jar + ${JAVA_SOURCES} + OUTPUT_NAME wpiunits + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} + ) set_property(TARGET wpiunits_jar PROPERTY FOLDER "java") install_jar(wpiunits_jar DESTINATION ${java_lib_dest}) diff --git a/wpiutil/CMakeLists.txt b/wpiutil/CMakeLists.txt index eb4a0a8f7c0..e20754db214 100644 --- a/wpiutil/CMakeLists.txt +++ b/wpiutil/CMakeLists.txt @@ -14,8 +14,6 @@ file( # Java bindings if(WITH_JAVA) - find_package(Java REQUIRED) - find_package(JNI REQUIRED) include(UseJava) if(NOT EXISTS "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/jackson/jackson-core-2.15.2.jar") @@ -47,10 +45,9 @@ if(WITH_JAVA) set(JAR_ROOT "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/quickbuf") message(STATUS "Downloading Quickbuf jarfile...") - file( - DOWNLOAD - "${BASE_URL}us/hebi/quickbuf/quickbuf-runtime/1.3.3/quickbuf-runtime-1.3.3.jar" - "${JAR_ROOT}/quickbuf-runtime-1.3.3.jar" + download_and_check( + "${BASE_URL}us/hebi/quickbuf/quickbuf-runtime/1.3.3/quickbuf-runtime-1.3.3.jar" + "${JAR_ROOT}/quickbuf-runtime-1.3.3.jar" ) message(STATUS "Downloaded.") @@ -58,8 +55,6 @@ if(WITH_JAVA) file(GLOB QUICKBUF_JAR ${WPILIB_BINARY_DIR}/wpiutil/thirdparty/quickbuf/*.jar) - set(CMAKE_JAVA_INCLUDE_PATH wpiutil.jar ${JACKSON_JARS} ${QUICKBUF_JAR}) - set(CMAKE_JNI_TARGET true) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java) @@ -69,6 +64,7 @@ if(WITH_JAVA) ${JAVA_SOURCES} INCLUDE_JARS ${JACKSON_JARS} ${QUICKBUF_JAR} OUTPUT_NAME wpiutil + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} GENERATE_NATIVE_HEADERS wpiutil_jni_headers ) set_property(TARGET wpiutil_jar PROPERTY FOLDER "java") @@ -90,7 +86,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file(GLOB WPIUTIL_SOURCES src/main/java/edu/wpi/first/util/*.java) file(GLOB WPIUTIL_CLEANUP_SOURCES src/main/java/edu/wpi/first/util/cleanup/*.java) @@ -108,6 +103,7 @@ if(WITH_JAVA_SOURCE) NAMESPACE "edu/wpi/first/util/function" ${WPIUTIL_FUNCTION_SOURCES} NAMESPACE "edu/wpi/first/util/sendable" ${WPIUTIL_SENDABLE_SOURCES} OUTPUT_NAME wpiutil-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(WPIUTIL_SRC_JAR_FILE TARGET wpiutil_src_jar PROPERTY JAR_FILE) @@ -176,7 +172,6 @@ if(NOT USE_SYSTEM_FMTLIB) wpiutil PUBLIC $ - $ ) else() find_package(fmt CONFIG REQUIRED) @@ -208,49 +203,36 @@ install( target_include_directories( wpiutil PUBLIC - $ $ - $ ) install(DIRECTORY src/main/native/thirdparty/memory/include/ DESTINATION "${include_dest}/wpiutil") target_include_directories( wpiutil - PUBLIC - $ - $ - $ + PUBLIC $ ) install(DIRECTORY src/main/native/thirdparty/json/include/ DESTINATION "${include_dest}/wpiutil") target_include_directories( wpiutil - PUBLIC - $ - $ + PUBLIC $ ) install(DIRECTORY src/main/native/thirdparty/llvm/include/ DESTINATION "${include_dest}/wpiutil") target_include_directories( wpiutil - PUBLIC - $ - $ + PUBLIC $ ) install(DIRECTORY src/main/native/thirdparty/mpack/include/ DESTINATION "${include_dest}/wpiutil") target_include_directories( wpiutil - PUBLIC - $ - $ + PUBLIC $ ) install(DIRECTORY src/main/native/thirdparty/sigslot/include/ DESTINATION "${include_dest}/wpiutil") target_include_directories( wpiutil - PUBLIC - $ - $ + PUBLIC $ ) install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpiutil") diff --git a/xrpVendordep/CMakeLists.txt b/xrpVendordep/CMakeLists.txt index 5099beb7603..e57c703417a 100644 --- a/xrpVendordep/CMakeLists.txt +++ b/xrpVendordep/CMakeLists.txt @@ -5,7 +5,6 @@ include(CompileWarnings) include(AddTest) if(WITH_JAVA) - find_package(Java REQUIRED) include(UseJava) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java) @@ -22,6 +21,7 @@ if(WITH_JAVA) wpiutil_jar wpilibj_jar OUTPUT_NAME xrpVendordep + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) set_property(TARGET xrpVendordep_jar PROPERTY FOLDER "java") @@ -34,7 +34,6 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) file(GLOB XRPVENDORDEP_SOURCES src/main/java/edu/wpi/first/wpilibj/xrp/*.java) add_jar( @@ -42,6 +41,7 @@ if(WITH_JAVA_SOURCE) RESOURCES NAMESPACE "edu/wpi/first/wpilibj/xrp" ${XRPVENDORDEP_SOURCES} OUTPUT_NAME xrpVendordep-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) get_property(xrpVendordep_src_JAR_FILE TARGET xrpVendordep_src_jar PROPERTY JAR_FILE) @@ -66,7 +66,7 @@ target_include_directories( $ ) -install(TARGETS xrpVendordep EXPORT xrpvendordep DESTINATION "${main_lib_dest}") +install(TARGETS xrpVendordep EXPORT xrpvendordep) export(TARGETS xrpVendordep FILE xrpvendordep.cmake NAMESPACE xrpvendordep::) install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/xrpVendordep") From 967105568ca530a119c007fa760b941e9e1e8bf3 Mon Sep 17 00:00:00 2001 From: Jade Date: Fri, 12 Jul 2024 06:01:54 +0800 Subject: [PATCH 07/20] [commands] Update requirements consistently (#6304) --- .../edu/wpi/first/wpilibj2/command/Command.java | 14 ++++++++++++++ .../first/wpilibj2/command/ConditionalCommand.java | 4 ++-- .../edu/wpi/first/wpilibj2/command/PIDCommand.java | 3 +-- .../wpilibj2/command/ParallelCommandGroup.java | 2 +- .../wpilibj2/command/ParallelDeadlineGroup.java | 2 +- .../first/wpilibj2/command/ParallelRaceGroup.java | 2 +- .../first/wpilibj2/command/ProfiledPIDCommand.java | 5 ++--- .../wpi/first/wpilibj2/command/RepeatCommand.java | 2 +- .../wpi/first/wpilibj2/command/SelectCommand.java | 2 +- .../wpilibj2/command/SequentialCommandGroup.java | 2 +- 10 files changed, 25 insertions(+), 13 deletions(-) diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java index 255291b933e..1364c1f3bd1 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java @@ -13,6 +13,7 @@ import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; +import java.util.Collection; import java.util.HashSet; import java.util.Set; import java.util.function.BooleanSupplier; @@ -96,6 +97,19 @@ public final void addRequirements(Subsystem... requirements) { } } + /** + * Adds the specified subsystems to the requirements of the command. The scheduler will prevent + * two commands that require the same subsystem from being scheduled simultaneously. + * + *

Note that the scheduler determines the requirements of a command when it is scheduled, so + * this method should normally be called from the command's constructor. + * + * @param requirements the requirements to add + */ + public final void addRequirements(Collection requirements) { + m_requirements.addAll(requirements); + } + /** * Gets the name of this Command. * diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java index 42db3f0b996..15c8674da7b 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java @@ -39,8 +39,8 @@ public ConditionalCommand(Command onTrue, Command onFalse, BooleanSupplier condi CommandScheduler.getInstance().registerComposedCommands(onTrue, onFalse); - m_requirements.addAll(m_onTrue.getRequirements()); - m_requirements.addAll(m_onFalse.getRequirements()); + addRequirements(m_onTrue.getRequirements()); + addRequirements(m_onFalse.getRequirements()); } @Override diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java index 26627fa30ff..fed674413b6 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java @@ -7,7 +7,6 @@ import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.math.controller.PIDController; -import java.util.Set; import java.util.function.DoubleConsumer; import java.util.function.DoubleSupplier; @@ -55,7 +54,7 @@ public PIDCommand( m_useOutput = useOutput; m_measurement = measurementSource; m_setpoint = setpointSource; - m_requirements.addAll(Set.of(requirements)); + addRequirements(requirements); } /** diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java index 6ea58698c60..cb5dcf0c0e2 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java @@ -55,7 +55,7 @@ public final void addCommands(Command... commands) { "Multiple commands in a parallel composition cannot require the same subsystems"); } m_commands.put(command, false); - m_requirements.addAll(command.getRequirements()); + addRequirements(command.getRequirements()); m_runWhenDisabled &= command.runsWhenDisabled(); if (command.getInterruptionBehavior() == InterruptionBehavior.kCancelSelf) { m_interruptBehavior = InterruptionBehavior.kCancelSelf; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java index eb576d75872..fae0542322a 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java @@ -85,7 +85,7 @@ public final void addCommands(Command... commands) { "Multiple commands in a parallel group cannot require the same subsystems"); } m_commands.put(command, false); - m_requirements.addAll(command.getRequirements()); + addRequirements(command.getRequirements()); m_runWhenDisabled &= command.runsWhenDisabled(); if (command.getInterruptionBehavior() == InterruptionBehavior.kCancelSelf) { m_interruptBehavior = InterruptionBehavior.kCancelSelf; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java index 39fe6114b41..538ab11d5d2 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java @@ -56,7 +56,7 @@ public final void addCommands(Command... commands) { "Multiple commands in a parallel composition cannot require the same subsystems"); } m_commands.add(command); - m_requirements.addAll(command.getRequirements()); + addRequirements(command.getRequirements()); m_runWhenDisabled &= command.runsWhenDisabled(); if (command.getInterruptionBehavior() == InterruptionBehavior.kCancelSelf) { m_interruptBehavior = InterruptionBehavior.kCancelSelf; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java index 4e82811739b..39bdf246c18 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java @@ -8,7 +8,6 @@ import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.math.controller.ProfiledPIDController; -import java.util.Set; import java.util.function.BiConsumer; import java.util.function.DoubleSupplier; import java.util.function.Supplier; @@ -58,7 +57,7 @@ public ProfiledPIDCommand( m_useOutput = useOutput; m_measurement = measurementSource; m_goal = goalSource; - m_requirements.addAll(Set.of(requirements)); + addRequirements(requirements); } /** @@ -86,7 +85,7 @@ public ProfiledPIDCommand( m_useOutput = useOutput; m_measurement = measurementSource; m_goal = () -> new State(goalSource.getAsDouble(), 0); - m_requirements.addAll(Set.of(requirements)); + addRequirements(requirements); } /** diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java index 70ff63c6103..6c64b4f2e4d 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java @@ -33,7 +33,7 @@ public class RepeatCommand extends Command { public RepeatCommand(Command command) { m_command = requireNonNullParam(command, "command", "RepeatCommand"); CommandScheduler.getInstance().registerComposedCommands(command); - m_requirements.addAll(command.getRequirements()); + addRequirements(command.getRequirements()); setName("Repeat(" + command.getName() + ")"); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java index 28d06eb0851..b888e98eb5f 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java @@ -47,7 +47,7 @@ public SelectCommand(Map commands, Supplier selector) { .registerComposedCommands(commands.values().toArray(new Command[] {})); for (Command command : m_commands.values()) { - m_requirements.addAll(command.getRequirements()); + addRequirements(command.getRequirements()); m_runsWhenDisabled &= command.runsWhenDisabled(); if (command.getInterruptionBehavior() == InterruptionBehavior.kCancelSelf) { m_interruptBehavior = InterruptionBehavior.kCancelSelf; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java index 87805972c38..905b8a6bbd3 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java @@ -49,7 +49,7 @@ public final void addCommands(Command... commands) { for (Command command : commands) { m_commands.add(command); - m_requirements.addAll(command.getRequirements()); + addRequirements(command.getRequirements()); m_runWhenDisabled &= command.runsWhenDisabled(); if (command.getInterruptionBehavior() == InterruptionBehavior.kCancelSelf) { m_interruptBehavior = InterruptionBehavior.kCancelSelf; From 19c28c2a769d489b2db4b4c823d34ff3e62ab782 Mon Sep 17 00:00:00 2001 From: Jade Date: Fri, 12 Jul 2024 21:51:21 +0800 Subject: [PATCH 08/20] [commands] Make requirements private (#6769) --- .../src/main/java/edu/wpi/first/wpilibj2/command/Command.java | 2 +- .../edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java | 2 +- .../edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java | 2 +- .../java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java | 2 +- .../src/main/native/include/frc2/command/Command.h | 1 + 5 files changed, 5 insertions(+), 4 deletions(-) diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java index 1364c1f3bd1..e64044cab35 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java @@ -30,7 +30,7 @@ */ public abstract class Command implements Sendable { /** Requirements set. */ - protected Set m_requirements = new HashSet<>(); + private final Set m_requirements = new HashSet<>(); /** Default constructor. */ @SuppressWarnings("this-escape") diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java index cb5dcf0c0e2..14d93b6961c 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java @@ -50,7 +50,7 @@ public final void addCommands(Command... commands) { CommandScheduler.getInstance().registerComposedCommands(commands); for (Command command : commands) { - if (!Collections.disjoint(command.getRequirements(), m_requirements)) { + if (!Collections.disjoint(command.getRequirements(), getRequirements())) { throw new IllegalArgumentException( "Multiple commands in a parallel composition cannot require the same subsystems"); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java index fae0542322a..86417f27b9c 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java @@ -80,7 +80,7 @@ public final void addCommands(Command... commands) { CommandScheduler.getInstance().registerComposedCommands(commands); for (Command command : commands) { - if (!Collections.disjoint(command.getRequirements(), m_requirements)) { + if (!Collections.disjoint(command.getRequirements(), getRequirements())) { throw new IllegalArgumentException( "Multiple commands in a parallel group cannot require the same subsystems"); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java index 538ab11d5d2..bd2b214d106 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java @@ -51,7 +51,7 @@ public final void addCommands(Command... commands) { CommandScheduler.getInstance().registerComposedCommands(commands); for (Command command : commands) { - if (!Collections.disjoint(command.getRequirements(), m_requirements)) { + if (!Collections.disjoint(command.getRequirements(), getRequirements())) { throw new IllegalArgumentException( "Multiple commands in a parallel composition cannot require the same subsystems"); } diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/Command.h b/wpilibNewCommands/src/main/native/include/frc2/command/Command.h index 4b508cfb194..c4af1afe81b 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/Command.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/Command.h @@ -484,6 +484,7 @@ class Command : public wpi::Sendable, public wpi::SendableHelper { protected: Command(); + private: /// Requirements set. wpi::SmallSet m_requirements; From e00bb2f07b8fc346d883ee0d208afc68b8660b28 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sat, 13 Jul 2024 00:51:55 -0400 Subject: [PATCH 09/20] [build] CMake: add some compiler flags from native-utils (#6825) --- CMakeLists.txt | 4 ++++ README-CMAKE.md | 2 ++ apriltag/CMakeLists.txt | 6 +++++- cmake/modules/CompileWarnings.cmake | 1 + wpiutil/CMakeLists.txt | 2 +- 5 files changed, 13 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4010ef9eb27..957114d2805 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,6 +30,10 @@ include(CPack) include(OptionValidation) set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS TRUE) +set(CMAKE_POSITION_INDEPENDENT_CODE TRUE) +if(MSVC) + add_compile_options(/Zc:__cplusplus) +endif() set_property(GLOBAL PROPERTY USE_FOLDERS ON) set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${WPILIB_BINARY_DIR}/lib) diff --git a/README-CMAKE.md b/README-CMAKE.md index e52d77ec2ef..3dde6d05114 100644 --- a/README-CMAKE.md +++ b/README-CMAKE.md @@ -71,6 +71,8 @@ The following build options are available: * Set this option to the location of the archive of the OpenCV Java bindings (it should be called opencv-xxx.jar, with the x'es being version numbers). NOTE: set it to the LOCATION of the file, not the file itself! * `NO_WERROR` (OFF Default) * This option will disable the `-Werror` compilation flag for non-MSVC builds. +* `WPILIB_TARGET_WARNINGS` + * Add compiler flags to this option to customize compiler options like warnings. ## Build Setup diff --git a/apriltag/CMakeLists.txt b/apriltag/CMakeLists.txt index 28a2751d577..9be0eaa2675 100644 --- a/apriltag/CMakeLists.txt +++ b/apriltag/CMakeLists.txt @@ -134,7 +134,11 @@ if(MSVC) else() target_compile_options( apriltag - PRIVATE -Wno-sign-compare -Wno-gnu-zero-variadic-macro-arguments -Wno-type-limits + PRIVATE + -Wno-sign-compare + -Wno-gnu-zero-variadic-macro-arguments + -Wno-type-limits + -Wno-format-nonliteral ) endif() diff --git a/cmake/modules/CompileWarnings.cmake b/cmake/modules/CompileWarnings.cmake index 5de103201e2..94d952ce5d7 100644 --- a/cmake/modules/CompileWarnings.cmake +++ b/cmake/modules/CompileWarnings.cmake @@ -5,6 +5,7 @@ macro(wpilib_target_warnings target) -pedantic -Wextra -Wno-unused-parameter + -Wformat=2 ${WPILIB_TARGET_WARNINGS} ) if(NOT NO_WERROR) diff --git a/wpiutil/CMakeLists.txt b/wpiutil/CMakeLists.txt index e20754db214..3b26931b182 100644 --- a/wpiutil/CMakeLists.txt +++ b/wpiutil/CMakeLists.txt @@ -151,7 +151,7 @@ target_compile_features(wpiutil PUBLIC cxx_std_20) if(MSVC) target_compile_options( wpiutil - PUBLIC /permissive- /Zc:preprocessor /Zc:throwingNew /MP /bigobj + PUBLIC /permissive- /Zc:preprocessor /Zc:__cplusplus /Zc:throwingNew /MP /bigobj /utf-8 ) target_compile_definitions(wpiutil PRIVATE -D_CRT_SECURE_NO_WARNINGS) endif() From deb5f3d7afacfa9aae37d3867517332664344425 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Fri, 12 Jul 2024 21:52:28 -0700 Subject: [PATCH 10/20] [wpimath] Exit early when parameterizing malformed spline (#6827) Currently, a max iteration heuristic is used to determine when a spline is malformed. Instead, we can report a failure immediately if dx and dy are too small, because the heading won't be accurate either. Fixes #6826. --- .../edu/wpi/first/math/spline/Spline.java | 9 ++++- .../math/spline/SplineParameterizer.java | 33 ++++++++++------- .../math/trajectory/TrajectoryGenerator.java | 2 +- .../main/native/include/frc/spline/Spline.h | 10 +++-- .../include/frc/spline/SplineParameterizer.h | 37 ++++++++++++------- .../frc/trajectory/TrajectoryGenerator.h | 2 +- .../math/spline/CubicHermiteSplineTest.java | 2 +- .../cpp/spline/CubicHermiteSplineTest.cpp | 2 +- 8 files changed, 61 insertions(+), 36 deletions(-) diff --git a/wpimath/src/main/java/edu/wpi/first/math/spline/Spline.java b/wpimath/src/main/java/edu/wpi/first/math/spline/Spline.java index dc6c5e69969..80db954380a 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/spline/Spline.java +++ b/wpimath/src/main/java/edu/wpi/first/math/spline/Spline.java @@ -7,6 +7,7 @@ import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import java.util.Arrays; +import java.util.Optional; import org.ejml.simple.SimpleMatrix; /** Represents a two-dimensional parametric spline that interpolates between two points. */ @@ -49,7 +50,7 @@ public abstract class Spline { * @param t The point t * @return The pose and curvature at that point. */ - public PoseWithCurvature getPoint(double t) { + public Optional getPoint(double t) { SimpleMatrix polynomialBases = new SimpleMatrix(m_degree + 1, 1); final var coefficients = getCoefficients(); @@ -86,10 +87,14 @@ public PoseWithCurvature getPoint(double t) { ddy = combined.get(5, 0) / t / t; } + if (Math.hypot(dx, dy) < 1e-6) { + return Optional.empty(); + } + // Find the curvature. final double curvature = (dx * ddy - ddx * dy) / ((dx * dx + dy * dy) * Math.hypot(dx, dy)); - return new PoseWithCurvature(new Pose2d(x, y, new Rotation2d(dx, dy)), curvature); + return Optional.of(new PoseWithCurvature(new Pose2d(x, y, new Rotation2d(dx, dy)), curvature)); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java b/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java index 36bddb1feb1..b08c8c78a8b 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java +++ b/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java @@ -38,6 +38,11 @@ public final class SplineParameterizer { private static final double kMaxDy = 0.00127; private static final double kMaxDtheta = 0.0872; + private static final String kMalformedSplineExceptionMsg = + "Could not parameterize a malformed spline. This means that you probably had two or more " + + "adjacent waypoints that were very close together with headings in opposing " + + "directions."; + /** * A malformed spline does not actually explode the LIFO stack size. Instead, the stack size stays * at a relatively small number (e.g. 30) and never decreases. Because of this, we must count @@ -99,39 +104,41 @@ public static List parameterize(Spline spline, double t0, dou var splinePoints = new ArrayList(); // The parameterization does not add the initial point. Let's add that. - splinePoints.add(spline.getPoint(t0)); + splinePoints.add(spline.getPoint(t0).get()); // We use an "explicit stack" to simulate recursion, instead of a recursive function call // This give us greater control, instead of a stack overflow var stack = new ArrayDeque(); stack.push(new StackContents(t0, t1)); - StackContents current; - PoseWithCurvature start; - PoseWithCurvature end; int iterations = 0; while (!stack.isEmpty()) { - current = stack.removeFirst(); - start = spline.getPoint(current.t0); - end = spline.getPoint(current.t1); + var current = stack.removeFirst(); + + var start = spline.getPoint(current.t0); + if (!start.isPresent()) { + throw new MalformedSplineException(kMalformedSplineExceptionMsg); + } + + var end = spline.getPoint(current.t1); + if (!end.isPresent()) { + throw new MalformedSplineException(kMalformedSplineExceptionMsg); + } - final var twist = start.poseMeters.log(end.poseMeters); + final var twist = start.get().poseMeters.log(end.get().poseMeters); if (Math.abs(twist.dy) > kMaxDy || Math.abs(twist.dx) > kMaxDx || Math.abs(twist.dtheta) > kMaxDtheta) { stack.addFirst(new StackContents((current.t0 + current.t1) / 2, current.t1)); stack.addFirst(new StackContents(current.t0, (current.t0 + current.t1) / 2)); } else { - splinePoints.add(spline.getPoint(current.t1)); + splinePoints.add(end.get()); } iterations++; if (iterations >= kMaxIterations) { - throw new MalformedSplineException( - "Could not parameterize a malformed spline. This means that you probably had two or " - + " more adjacent waypoints that were very close together with headings in " - + "opposing directions."); + throw new MalformedSplineException(kMalformedSplineExceptionMsg); } } diff --git a/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryGenerator.java b/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryGenerator.java index 3de3effd826..a17d5fb1bc1 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryGenerator.java +++ b/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryGenerator.java @@ -246,7 +246,7 @@ public static List splinePointsFromSplines(Spline[] splines) var splinePoints = new ArrayList(); // Add the first point to the vector. - splinePoints.add(splines[0].getPoint(0.0)); + splinePoints.add(splines[0].getPoint(0.0).get()); // Iterate through the vector and parameterize each spline, adding the // parameterized points to the final vector. diff --git a/wpimath/src/main/native/include/frc/spline/Spline.h b/wpimath/src/main/native/include/frc/spline/Spline.h index 257b167f38c..9b369e31b62 100644 --- a/wpimath/src/main/native/include/frc/spline/Spline.h +++ b/wpimath/src/main/native/include/frc/spline/Spline.h @@ -4,8 +4,8 @@ #pragma once +#include #include -#include #include @@ -57,7 +57,7 @@ class Spline { * @param t The point t * @return The pose and curvature at that point. */ - PoseWithCurvature GetPoint(double t) const { + std::optional GetPoint(double t) const { Vectord polynomialBases; // Populate the polynomial bases @@ -88,11 +88,15 @@ class Spline { ddy = combined(5) / t / t; } + if (std::hypot(dx, dy) < 1e-6) { + return std::nullopt; + } + // Find the curvature. const auto curvature = (dx * ddy - ddx * dy) / ((dx * dx + dy * dy) * std::hypot(dx, dy)); - return { + return PoseWithCurvature{ {FromVector(combined.template block<2, 1>(0, 0)), Rotation2d{dx, dy}}, units::curvature_t{curvature}}; } diff --git a/wpimath/src/main/native/include/frc/spline/SplineParameterizer.h b/wpimath/src/main/native/include/frc/spline/SplineParameterizer.h index e1d2d5230de..1b49656d6a8 100644 --- a/wpimath/src/main/native/include/frc/spline/SplineParameterizer.h +++ b/wpimath/src/main/native/include/frc/spline/SplineParameterizer.h @@ -72,28 +72,41 @@ class WPILIB_DLLEXPORT SplineParameterizer { static std::vector Parameterize(const Spline& spline, double t0 = 0.0, double t1 = 1.0) { + constexpr const char* kMalformedSplineExceptionMsg = + "Could not parameterize a malformed spline. This means that you " + "probably had two or more adjacent waypoints that were very close " + "together with headings in opposing directions."; std::vector splinePoints; // The parameterization does not add the initial point. Let's add that. - splinePoints.push_back(spline.GetPoint(t0)); + if (auto point = spline.GetPoint(t0)) { + splinePoints.push_back(point.value()); + } else { + throw MalformedSplineException(kMalformedSplineExceptionMsg); + } // We use an "explicit stack" to simulate recursion, instead of a recursive // function call This give us greater control, instead of a stack overflow std::stack stack; stack.emplace(StackContents{t0, t1}); - StackContents current; - PoseWithCurvature start; - PoseWithCurvature end; int iterations = 0; while (!stack.empty()) { - current = stack.top(); + auto current = stack.top(); stack.pop(); - start = spline.GetPoint(current.t0); - end = spline.GetPoint(current.t1); - const auto twist = start.first.Log(end.first); + auto start = spline.GetPoint(current.t0); + if (!start) { + throw MalformedSplineException(kMalformedSplineExceptionMsg); + } + + auto end = spline.GetPoint(current.t1); + if (!end) { + throw MalformedSplineException(kMalformedSplineExceptionMsg); + } + + const auto twist = start.value().first.Log(end.value().first); if (units::math::abs(twist.dy) > kMaxDy || units::math::abs(twist.dx) > kMaxDx || @@ -101,15 +114,11 @@ class WPILIB_DLLEXPORT SplineParameterizer { stack.emplace(StackContents{(current.t0 + current.t1) / 2, current.t1}); stack.emplace(StackContents{current.t0, (current.t0 + current.t1) / 2}); } else { - splinePoints.push_back(spline.GetPoint(current.t1)); + splinePoints.push_back(end.value()); } if (iterations++ >= kMaxIterations) { - throw MalformedSplineException( - "Could not parameterize a malformed spline. " - "This means that you probably had two or more adjacent " - "waypoints that were very close together with headings " - "in opposing directions."); + throw MalformedSplineException(kMalformedSplineExceptionMsg); } } diff --git a/wpimath/src/main/native/include/frc/trajectory/TrajectoryGenerator.h b/wpimath/src/main/native/include/frc/trajectory/TrajectoryGenerator.h index 3df6c89d3e2..f7076bce1d9 100644 --- a/wpimath/src/main/native/include/frc/trajectory/TrajectoryGenerator.h +++ b/wpimath/src/main/native/include/frc/trajectory/TrajectoryGenerator.h @@ -99,7 +99,7 @@ class WPILIB_DLLEXPORT TrajectoryGenerator { std::vector splinePoints; // Add the first point to the vector. - splinePoints.push_back(splines.front().GetPoint(0.0)); + splinePoints.push_back(splines.front().GetPoint(0.0).value()); // Iterate through the vector and parameterize each spline, adding the // parameterized points to the final vector. diff --git a/wpimath/src/test/java/edu/wpi/first/math/spline/CubicHermiteSplineTest.java b/wpimath/src/test/java/edu/wpi/first/math/spline/CubicHermiteSplineTest.java index 4552c20a2ba..74b06947c7f 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/spline/CubicHermiteSplineTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/spline/CubicHermiteSplineTest.java @@ -36,7 +36,7 @@ private void run(Pose2d a, List waypoints, Pose2d b) { var poses = new ArrayList(); - poses.add(splines[0].getPoint(0.0)); + poses.add(splines[0].getPoint(0.0).get()); for (var spline : splines) { poses.addAll(SplineParameterizer.parameterize(spline)); diff --git a/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp b/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp index 3a4acc0e65e..d16444cd675 100644 --- a/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp +++ b/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp @@ -30,7 +30,7 @@ class CubicHermiteSplineTest : public ::testing::Test { SplineHelper::CubicSplinesFromControlVectors(startCV, waypoints, endCV); std::vector::PoseWithCurvature> poses; - poses.push_back(splines[0].GetPoint(0.0)); + poses.push_back(splines[0].GetPoint(0.0).value()); for (auto&& spline : splines) { auto x = SplineParameterizer::Parameterize(spline); From fc44737a49ff0c78d5f10a0026a0125eaf0552e6 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sat, 13 Jul 2024 06:52:30 -0700 Subject: [PATCH 11/20] [commands] Suppress this-escape warnings (#6828) --- .../java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java | 1 + .../main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java | 1 + .../edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java | 1 + .../edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java | 1 + .../java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java | 1 + .../java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java | 2 ++ .../main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java | 1 + .../edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java | 1 + 8 files changed, 9 insertions(+) diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java index 15c8674da7b..1d2661afb6a 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java @@ -32,6 +32,7 @@ public class ConditionalCommand extends Command { * @param onFalse the command to run if the condition is false * @param condition the condition to determine which command to run */ + @SuppressWarnings("this-escape") public ConditionalCommand(Command onTrue, Command onFalse, BooleanSupplier condition) { m_onTrue = requireNonNullParam(onTrue, "onTrue", "ConditionalCommand"); m_onFalse = requireNonNullParam(onFalse, "onFalse", "ConditionalCommand"); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java index fed674413b6..360e15bf9d4 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java @@ -39,6 +39,7 @@ public class PIDCommand extends Command { * @param useOutput the controller's output * @param requirements the subsystems required by this command */ + @SuppressWarnings("this-escape") public PIDCommand( PIDController controller, DoubleSupplier measurementSource, diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java index 14d93b6961c..0fc31876ce4 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java @@ -32,6 +32,7 @@ public class ParallelCommandGroup extends Command { * * @param commands the commands to include in this composition. */ + @SuppressWarnings("this-escape") public ParallelCommandGroup(Command... commands) { addCommands(commands); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java index 86417f27b9c..2286cee7de8 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java @@ -40,6 +40,7 @@ public class ParallelDeadlineGroup extends Command { * @param otherCommands the other commands to be executed * @throws IllegalArgumentException if the deadline command is also in the otherCommands argument */ + @SuppressWarnings("this-escape") public ParallelDeadlineGroup(Command deadline, Command... otherCommands) { setDeadline(deadline); addCommands(otherCommands); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java index bd2b214d106..36eaf275431 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java @@ -32,6 +32,7 @@ public class ParallelRaceGroup extends Command { * * @param commands the commands to include in this composition. */ + @SuppressWarnings("this-escape") public ParallelRaceGroup(Command... commands) { addCommands(commands); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java index 39bdf246c18..b22ff51c4a3 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java @@ -42,6 +42,7 @@ public class ProfiledPIDCommand extends Command { * @param useOutput the controller's output * @param requirements the subsystems required by this command */ + @SuppressWarnings("this-escape") public ProfiledPIDCommand( ProfiledPIDController controller, DoubleSupplier measurementSource, @@ -70,6 +71,7 @@ public ProfiledPIDCommand( * @param useOutput the controller's output * @param requirements the subsystems required by this command */ + @SuppressWarnings("this-escape") public ProfiledPIDCommand( ProfiledPIDController controller, DoubleSupplier measurementSource, diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java index b888e98eb5f..2712b4508e6 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java @@ -38,6 +38,7 @@ public class SelectCommand extends Command { * @param commands the map of commands to choose from * @param selector the selector to determine which command to run */ + @SuppressWarnings("this-escape") public SelectCommand(Map commands, Supplier selector) { m_commands = requireNonNullParam(commands, "commands", "SelectCommand"); m_selector = requireNonNullParam(selector, "selector", "SelectCommand"); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java index 905b8a6bbd3..5d6b2cd1e58 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java @@ -29,6 +29,7 @@ public class SequentialCommandGroup extends Command { * * @param commands the commands to include in this composition. */ + @SuppressWarnings("this-escape") public SequentialCommandGroup(Command... commands) { addCommands(commands); } From 6b9d41182fcc762f57f3523ab0e7d1a4ee811c12 Mon Sep 17 00:00:00 2001 From: Jade Date: Tue, 16 Jul 2024 01:17:35 +0800 Subject: [PATCH 12/20] [sim] Fix WS sending 1 and 0 instead of booleans (#6836) --- .../src/main/native/cpp/WSProvider_SimDevice.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_SimDevice.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_SimDevice.cpp index 93852b6703b..7c3d710f47c 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_SimDevice.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_SimDevice.cpp @@ -188,7 +188,8 @@ void HALSimWSProviderSimDevice::OnValueChanged(SimDeviceValueData* valueData, if (ws) { switch (value->type) { case HAL_BOOLEAN: - ProcessHalCallback({{valueData->key, value->data.v_boolean}}); + ProcessHalCallback( + {{valueData->key, static_cast(value->data.v_boolean)}}); break; case HAL_DOUBLE: ProcessHalCallback( From 5825bf46d853dbd49e36a078c6ca1d8d6dfade7e Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Mon, 15 Jul 2024 14:41:40 -0700 Subject: [PATCH 13/20] [upstream_utils] Suppress has_denorm deprecation in Eigen (#6833) MSVC doesn't yet claim C++23 compliance for c++latest, so we have to be less specific in the preprocessor check. --- .../eigen_patches/0001-Disable-warnings.patch | 4 +- .../eigen_patches/0002-Intellisense-fix.patch | 2 +- ...orm-and-has_denorm_loss-deprecation-.patch | 89 +++++++++++++++++++ upstream_utils/update_eigen.py | 1 + .../Eigen/src/Core/arch/Default/BFloat16.h | 8 -- .../Eigen/src/Core/arch/Default/Half.h | 8 -- 6 files changed, 93 insertions(+), 19 deletions(-) create mode 100644 upstream_utils/eigen_patches/0003-Suppress-has_denorm-and-has_denorm_loss-deprecation-.patch diff --git a/upstream_utils/eigen_patches/0001-Disable-warnings.patch b/upstream_utils/eigen_patches/0001-Disable-warnings.patch index ace8aa06ace..ca9aee77ec8 100644 --- a/upstream_utils/eigen_patches/0001-Disable-warnings.patch +++ b/upstream_utils/eigen_patches/0001-Disable-warnings.patch @@ -1,14 +1,14 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Wed, 18 May 2022 09:14:24 -0700 -Subject: [PATCH 1/2] Disable warnings +Subject: [PATCH 1/3] Disable warnings --- Eigen/src/Core/util/DisableStupidWarnings.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Eigen/src/Core/util/DisableStupidWarnings.h b/Eigen/src/Core/util/DisableStupidWarnings.h -index 32a427d852355a51dc4263d81498554ff4c3cbba..9f3e3f5b0f15518377c9a8283fd58081902896f2 100644 +index 32a427d852355a51dc4263d81498554ff4c3cbba..1182198231ab784346f8d80838363e4a0abba2ba 100644 --- a/Eigen/src/Core/util/DisableStupidWarnings.h +++ b/Eigen/src/Core/util/DisableStupidWarnings.h @@ -81,6 +81,12 @@ diff --git a/upstream_utils/eigen_patches/0002-Intellisense-fix.patch b/upstream_utils/eigen_patches/0002-Intellisense-fix.patch index 46ac050cfe7..2c7d477f290 100644 --- a/upstream_utils/eigen_patches/0002-Intellisense-fix.patch +++ b/upstream_utils/eigen_patches/0002-Intellisense-fix.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Fri, 20 Jan 2023 23:41:56 -0800 -Subject: [PATCH 2/2] Intellisense fix +Subject: [PATCH 2/3] Intellisense fix --- Eigen/src/Core/util/ConfigureVectorization.h | 7 +++++++ diff --git a/upstream_utils/eigen_patches/0003-Suppress-has_denorm-and-has_denorm_loss-deprecation-.patch b/upstream_utils/eigen_patches/0003-Suppress-has_denorm-and-has_denorm_loss-deprecation-.patch new file mode 100644 index 00000000000..d89c94f3a55 --- /dev/null +++ b/upstream_utils/eigen_patches/0003-Suppress-has_denorm-and-has_denorm_loss-deprecation-.patch @@ -0,0 +1,89 @@ +From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 +From: Tyler Veness +Date: Sat, 13 Jul 2024 18:51:32 -0700 +Subject: [PATCH 3/3] Suppress has_denorm and has_denorm_loss deprecation + warnings + +MSVC doesn't yet claim C++23 compliance for c++latest, so we have to be +less specific in the preprocessor check. +--- + Eigen/src/Core/arch/Default/BFloat16.h | 8 -------- + Eigen/src/Core/arch/Default/Half.h | 8 -------- + 2 files changed, 16 deletions(-) + +diff --git a/Eigen/src/Core/arch/Default/BFloat16.h b/Eigen/src/Core/arch/Default/BFloat16.h +index 9e79a39a4c81d3c08868e3b70e64d56118a4efe8..14f0524a3b0e4ff836b77092949caafa0949a18c 100644 +--- a/Eigen/src/Core/arch/Default/BFloat16.h ++++ b/Eigen/src/Core/arch/Default/BFloat16.h +@@ -139,15 +139,11 @@ struct numeric_limits_bfloat16_impl { + static EIGEN_CONSTEXPR const bool has_infinity = true; + static EIGEN_CONSTEXPR const bool has_quiet_NaN = true; + static EIGEN_CONSTEXPR const bool has_signaling_NaN = true; +-#if __cplusplus >= 202302L + EIGEN_DIAGNOSTICS(push) + EIGEN_DISABLE_DEPRECATED_WARNING +-#endif + static EIGEN_CONSTEXPR const std::float_denorm_style has_denorm = std::denorm_present; + static EIGEN_CONSTEXPR const bool has_denorm_loss = false; +-#if __cplusplus >= 202302L + EIGEN_DIAGNOSTICS(pop) +-#endif + static EIGEN_CONSTEXPR const std::float_round_style round_style = std::numeric_limits::round_style; + static EIGEN_CONSTEXPR const bool is_iec559 = true; + // The C++ standard defines this as "true if the set of values representable +@@ -194,17 +190,13 @@ template + EIGEN_CONSTEXPR const bool numeric_limits_bfloat16_impl::has_quiet_NaN; + template + EIGEN_CONSTEXPR const bool numeric_limits_bfloat16_impl::has_signaling_NaN; +-#if __cplusplus >= 202302L + EIGEN_DIAGNOSTICS(push) + EIGEN_DISABLE_DEPRECATED_WARNING +-#endif + template + EIGEN_CONSTEXPR const std::float_denorm_style numeric_limits_bfloat16_impl::has_denorm; + template + EIGEN_CONSTEXPR const bool numeric_limits_bfloat16_impl::has_denorm_loss; +-#if __cplusplus >= 202302L + EIGEN_DIAGNOSTICS(pop) +-#endif + template + EIGEN_CONSTEXPR const std::float_round_style numeric_limits_bfloat16_impl::round_style; + template +diff --git a/Eigen/src/Core/arch/Default/Half.h b/Eigen/src/Core/arch/Default/Half.h +index 7754e8f27261f5e10eec8e1125b4869e01e5dde8..90d65c5e3cb099374179223d4b3e50d4991b06cd 100644 +--- a/Eigen/src/Core/arch/Default/Half.h ++++ b/Eigen/src/Core/arch/Default/Half.h +@@ -208,15 +208,11 @@ struct numeric_limits_half_impl { + static EIGEN_CONSTEXPR const bool has_infinity = true; + static EIGEN_CONSTEXPR const bool has_quiet_NaN = true; + static EIGEN_CONSTEXPR const bool has_signaling_NaN = true; +-#if __cplusplus >= 202302L + EIGEN_DIAGNOSTICS(push) + EIGEN_DISABLE_DEPRECATED_WARNING +-#endif + static EIGEN_CONSTEXPR const std::float_denorm_style has_denorm = std::denorm_present; + static EIGEN_CONSTEXPR const bool has_denorm_loss = false; +-#if __cplusplus >= 202302L + EIGEN_DIAGNOSTICS(pop) +-#endif + static EIGEN_CONSTEXPR const std::float_round_style round_style = std::round_to_nearest; + static EIGEN_CONSTEXPR const bool is_iec559 = true; + // The C++ standard defines this as "true if the set of values representable +@@ -263,17 +259,13 @@ template + EIGEN_CONSTEXPR const bool numeric_limits_half_impl::has_quiet_NaN; + template + EIGEN_CONSTEXPR const bool numeric_limits_half_impl::has_signaling_NaN; +-#if __cplusplus >= 202302L + EIGEN_DIAGNOSTICS(push) + EIGEN_DISABLE_DEPRECATED_WARNING +-#endif + template + EIGEN_CONSTEXPR const std::float_denorm_style numeric_limits_half_impl::has_denorm; + template + EIGEN_CONSTEXPR const bool numeric_limits_half_impl::has_denorm_loss; +-#if __cplusplus >= 202302L + EIGEN_DIAGNOSTICS(pop) +-#endif + template + EIGEN_CONSTEXPR const std::float_round_style numeric_limits_half_impl::round_style; + template diff --git a/upstream_utils/update_eigen.py b/upstream_utils/update_eigen.py index fd8cfb4ef60..66c82385e97 100755 --- a/upstream_utils/update_eigen.py +++ b/upstream_utils/update_eigen.py @@ -109,6 +109,7 @@ def main(): for f in [ "0001-Disable-warnings.patch", "0002-Intellisense-fix.patch", + "0003-Suppress-has_denorm-and-has_denorm_loss-deprecation-.patch", ]: git_am(os.path.join(wpilib_root, "upstream_utils/eigen_patches", f)) diff --git a/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/BFloat16.h b/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/BFloat16.h index 9e79a39a4c8..14f0524a3b0 100644 --- a/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/BFloat16.h +++ b/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/BFloat16.h @@ -139,15 +139,11 @@ struct numeric_limits_bfloat16_impl { static EIGEN_CONSTEXPR const bool has_infinity = true; static EIGEN_CONSTEXPR const bool has_quiet_NaN = true; static EIGEN_CONSTEXPR const bool has_signaling_NaN = true; -#if __cplusplus >= 202302L EIGEN_DIAGNOSTICS(push) EIGEN_DISABLE_DEPRECATED_WARNING -#endif static EIGEN_CONSTEXPR const std::float_denorm_style has_denorm = std::denorm_present; static EIGEN_CONSTEXPR const bool has_denorm_loss = false; -#if __cplusplus >= 202302L EIGEN_DIAGNOSTICS(pop) -#endif static EIGEN_CONSTEXPR const std::float_round_style round_style = std::numeric_limits::round_style; static EIGEN_CONSTEXPR const bool is_iec559 = true; // The C++ standard defines this as "true if the set of values representable @@ -194,17 +190,13 @@ template EIGEN_CONSTEXPR const bool numeric_limits_bfloat16_impl::has_quiet_NaN; template EIGEN_CONSTEXPR const bool numeric_limits_bfloat16_impl::has_signaling_NaN; -#if __cplusplus >= 202302L EIGEN_DIAGNOSTICS(push) EIGEN_DISABLE_DEPRECATED_WARNING -#endif template EIGEN_CONSTEXPR const std::float_denorm_style numeric_limits_bfloat16_impl::has_denorm; template EIGEN_CONSTEXPR const bool numeric_limits_bfloat16_impl::has_denorm_loss; -#if __cplusplus >= 202302L EIGEN_DIAGNOSTICS(pop) -#endif template EIGEN_CONSTEXPR const std::float_round_style numeric_limits_bfloat16_impl::round_style; template diff --git a/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/Half.h b/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/Half.h index 7754e8f2726..90d65c5e3cb 100644 --- a/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/Half.h +++ b/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/Half.h @@ -208,15 +208,11 @@ struct numeric_limits_half_impl { static EIGEN_CONSTEXPR const bool has_infinity = true; static EIGEN_CONSTEXPR const bool has_quiet_NaN = true; static EIGEN_CONSTEXPR const bool has_signaling_NaN = true; -#if __cplusplus >= 202302L EIGEN_DIAGNOSTICS(push) EIGEN_DISABLE_DEPRECATED_WARNING -#endif static EIGEN_CONSTEXPR const std::float_denorm_style has_denorm = std::denorm_present; static EIGEN_CONSTEXPR const bool has_denorm_loss = false; -#if __cplusplus >= 202302L EIGEN_DIAGNOSTICS(pop) -#endif static EIGEN_CONSTEXPR const std::float_round_style round_style = std::round_to_nearest; static EIGEN_CONSTEXPR const bool is_iec559 = true; // The C++ standard defines this as "true if the set of values representable @@ -263,17 +259,13 @@ template EIGEN_CONSTEXPR const bool numeric_limits_half_impl::has_quiet_NaN; template EIGEN_CONSTEXPR const bool numeric_limits_half_impl::has_signaling_NaN; -#if __cplusplus >= 202302L EIGEN_DIAGNOSTICS(push) EIGEN_DISABLE_DEPRECATED_WARNING -#endif template EIGEN_CONSTEXPR const std::float_denorm_style numeric_limits_half_impl::has_denorm; template EIGEN_CONSTEXPR const bool numeric_limits_half_impl::has_denorm_loss; -#if __cplusplus >= 202302L EIGEN_DIAGNOSTICS(pop) -#endif template EIGEN_CONSTEXPR const std::float_round_style numeric_limits_half_impl::round_style; template From 912d9b220192271b4aa98447dadaac085f98663f Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Mon, 15 Jul 2024 14:50:19 -0700 Subject: [PATCH 14/20] [upstream_utils] Fix LLVM's AlignedCharArrayUnion for C++23 (#6830) C++23 deprecated std::aligned_union_t. --- ...move-StringRef-ArrayRef-and-Optional.patch | 2 +- ...-calls-in-parens-for-Windows-warning.patch | 2 +- ...-Change-unique_function-storage-size.patch | 2 +- .../llvm_patches/0004-Threading-updates.patch | 2 +- .../0005-ifdef-guard-safety.patch | 2 +- .../0006-Explicitly-use-std.patch | 2 +- .../0007-Remove-format_provider.patch | 2 +- .../0008-Add-compiler-warning-pragmas.patch | 2 +- .../0009-Remove-unused-functions.patch | 2 +- .../0010-Detemplatize-SmallVectorBase.patch | 2 +- .../0011-Add-vectors-to-raw_ostream.patch | 2 +- .../0012-Extra-collections-features.patch | 2 +- .../0013-EpochTracker-ABI-macro.patch | 2 +- .../0014-Delete-numbers-from-MathExtras.patch | 2 +- .../llvm_patches/0015-Add-lerp-and-sgn.patch | 2 +- .../llvm_patches/0016-Fixup-includes.patch | 2 +- ...-std-is_trivially_copy_constructible.patch | 2 +- .../llvm_patches/0018-Windows-support.patch | 2 +- .../llvm_patches/0019-Prefer-fmtlib.patch | 2 +- .../llvm_patches/0020-Prefer-wpi-s-fs.h.patch | 2 +- .../0021-Remove-unused-functions.patch | 2 +- .../0022-OS-specific-changes.patch | 2 +- ...3-Use-SmallVector-for-UTF-conversion.patch | 2 +- ...o-use-static-pointers-in-raw_ostream.patch | 2 +- .../0025-constexpr-endian-byte-swap.patch | 2 +- ...-from-STLExtras.h-into-PointerUnion..patch | 2 +- ...-Remove-StringMap-test-for-llvm-sort.patch | 2 +- ...0028-Unused-variable-in-release-mode.patch | 2 +- .../0029-Use-C-20-bit-header.patch | 2 +- ...0-Remove-DenseMap-GTest-printer-test.patch | 2 +- ...ace-deprecated-std-aligned_storage_t.patch | 2 +- ...-raw_ostream-Add-SetNumBytesInBuffer.patch | 2 +- .../0033-type_traits.h-Add-is_constexpr.patch | 2 +- ...emoved-raw_string_ostream-write_impl.patch | 2 +- ...ove-auto-conversion-from-raw_ostream.patch | 2 +- .../0036-Add-SmallVector-erase_if.patch | 2 +- ...7-Fix-AlignedCharArrayUnion-for-C-23.patch | 39 +++++++++++++++++++ upstream_utils/update_llvm.py | 1 + .../thirdparty/llvm/include/wpi/AlignOf.h | 14 +++---- 39 files changed, 81 insertions(+), 45 deletions(-) create mode 100644 upstream_utils/llvm_patches/0037-Fix-AlignedCharArrayUnion-for-C-23.patch diff --git a/upstream_utils/llvm_patches/0001-Remove-StringRef-ArrayRef-and-Optional.patch b/upstream_utils/llvm_patches/0001-Remove-StringRef-ArrayRef-and-Optional.patch index 7ec8a38696e..a1c558bcb3d 100644 --- a/upstream_utils/llvm_patches/0001-Remove-StringRef-ArrayRef-and-Optional.patch +++ b/upstream_utils/llvm_patches/0001-Remove-StringRef-ArrayRef-and-Optional.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:09:18 -0400 -Subject: [PATCH 01/36] Remove StringRef, ArrayRef, and Optional +Subject: [PATCH 01/37] Remove StringRef, ArrayRef, and Optional --- llvm/include/llvm/ADT/PointerUnion.h | 1 - diff --git a/upstream_utils/llvm_patches/0002-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch b/upstream_utils/llvm_patches/0002-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch index 1e4335b5e89..51b7215c2c5 100644 --- a/upstream_utils/llvm_patches/0002-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch +++ b/upstream_utils/llvm_patches/0002-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:12:41 -0400 -Subject: [PATCH 02/36] Wrap std::min/max calls in parens, for Windows warnings +Subject: [PATCH 02/37] Wrap std::min/max calls in parens, for Windows warnings --- llvm/include/llvm/ADT/DenseMap.h | 4 ++-- diff --git a/upstream_utils/llvm_patches/0003-Change-unique_function-storage-size.patch b/upstream_utils/llvm_patches/0003-Change-unique_function-storage-size.patch index ff920af4b52..dfc643346e3 100644 --- a/upstream_utils/llvm_patches/0003-Change-unique_function-storage-size.patch +++ b/upstream_utils/llvm_patches/0003-Change-unique_function-storage-size.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:13:55 -0400 -Subject: [PATCH 03/36] Change unique_function storage size +Subject: [PATCH 03/37] Change unique_function storage size --- llvm/include/llvm/ADT/FunctionExtras.h | 4 ++-- diff --git a/upstream_utils/llvm_patches/0004-Threading-updates.patch b/upstream_utils/llvm_patches/0004-Threading-updates.patch index 894050c88d9..cee1b2eb6da 100644 --- a/upstream_utils/llvm_patches/0004-Threading-updates.patch +++ b/upstream_utils/llvm_patches/0004-Threading-updates.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:17:19 -0400 -Subject: [PATCH 04/36] Threading updates +Subject: [PATCH 04/37] Threading updates - Remove guards for threads and exception - Prefer scope gaurd over lock gaurd diff --git a/upstream_utils/llvm_patches/0005-ifdef-guard-safety.patch b/upstream_utils/llvm_patches/0005-ifdef-guard-safety.patch index 50d93406cf7..fcb8e5c3738 100644 --- a/upstream_utils/llvm_patches/0005-ifdef-guard-safety.patch +++ b/upstream_utils/llvm_patches/0005-ifdef-guard-safety.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:28:13 -0400 -Subject: [PATCH 05/36] \#ifdef guard safety +Subject: [PATCH 05/37] \#ifdef guard safety Prevents redefinition if someone is pulling in real LLVM, since the macros are in global namespace --- diff --git a/upstream_utils/llvm_patches/0006-Explicitly-use-std.patch b/upstream_utils/llvm_patches/0006-Explicitly-use-std.patch index 2fffd4a5de8..2f8ee1aafa4 100644 --- a/upstream_utils/llvm_patches/0006-Explicitly-use-std.patch +++ b/upstream_utils/llvm_patches/0006-Explicitly-use-std.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:37:34 -0400 -Subject: [PATCH 06/36] Explicitly use std:: +Subject: [PATCH 06/37] Explicitly use std:: --- llvm/include/llvm/ADT/SmallSet.h | 2 +- diff --git a/upstream_utils/llvm_patches/0007-Remove-format_provider.patch b/upstream_utils/llvm_patches/0007-Remove-format_provider.patch index 914aeb183ef..dc76e10c8d9 100644 --- a/upstream_utils/llvm_patches/0007-Remove-format_provider.patch +++ b/upstream_utils/llvm_patches/0007-Remove-format_provider.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:53:50 -0400 -Subject: [PATCH 07/36] Remove format_provider +Subject: [PATCH 07/37] Remove format_provider --- llvm/include/llvm/Support/Chrono.h | 114 ------------------------ diff --git a/upstream_utils/llvm_patches/0008-Add-compiler-warning-pragmas.patch b/upstream_utils/llvm_patches/0008-Add-compiler-warning-pragmas.patch index f5996fd9668..a325299c074 100644 --- a/upstream_utils/llvm_patches/0008-Add-compiler-warning-pragmas.patch +++ b/upstream_utils/llvm_patches/0008-Add-compiler-warning-pragmas.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 13:34:07 -0400 -Subject: [PATCH 08/36] Add compiler warning pragmas +Subject: [PATCH 08/37] Add compiler warning pragmas --- llvm/include/llvm/ADT/FunctionExtras.h | 11 +++++++++++ diff --git a/upstream_utils/llvm_patches/0009-Remove-unused-functions.patch b/upstream_utils/llvm_patches/0009-Remove-unused-functions.patch index 071e7891297..110c273bdf2 100644 --- a/upstream_utils/llvm_patches/0009-Remove-unused-functions.patch +++ b/upstream_utils/llvm_patches/0009-Remove-unused-functions.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 13:43:50 -0400 -Subject: [PATCH 09/36] Remove unused functions +Subject: [PATCH 09/37] Remove unused functions --- llvm/include/llvm/ADT/SmallString.h | 79 ------ diff --git a/upstream_utils/llvm_patches/0010-Detemplatize-SmallVectorBase.patch b/upstream_utils/llvm_patches/0010-Detemplatize-SmallVectorBase.patch index cdb642e87c5..a05d7019a8e 100644 --- a/upstream_utils/llvm_patches/0010-Detemplatize-SmallVectorBase.patch +++ b/upstream_utils/llvm_patches/0010-Detemplatize-SmallVectorBase.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Thu, 5 May 2022 23:18:34 -0400 -Subject: [PATCH 10/36] Detemplatize SmallVectorBase +Subject: [PATCH 10/37] Detemplatize SmallVectorBase --- llvm/include/llvm/ADT/SmallVector.h | 35 ++++++++++----------------- diff --git a/upstream_utils/llvm_patches/0011-Add-vectors-to-raw_ostream.patch b/upstream_utils/llvm_patches/0011-Add-vectors-to-raw_ostream.patch index d9610107453..6d45796efd6 100644 --- a/upstream_utils/llvm_patches/0011-Add-vectors-to-raw_ostream.patch +++ b/upstream_utils/llvm_patches/0011-Add-vectors-to-raw_ostream.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 13:48:59 -0400 -Subject: [PATCH 11/36] Add vectors to raw_ostream +Subject: [PATCH 11/37] Add vectors to raw_ostream --- llvm/include/llvm/Support/raw_ostream.h | 115 ++++++++++++++++++++++++ diff --git a/upstream_utils/llvm_patches/0012-Extra-collections-features.patch b/upstream_utils/llvm_patches/0012-Extra-collections-features.patch index 42c18074880..2d4243eae73 100644 --- a/upstream_utils/llvm_patches/0012-Extra-collections-features.patch +++ b/upstream_utils/llvm_patches/0012-Extra-collections-features.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Tue, 3 May 2022 22:16:10 -0400 -Subject: [PATCH 12/36] Extra collections features +Subject: [PATCH 12/37] Extra collections features --- llvm/include/llvm/ADT/StringMap.h | 103 +++++++++++++++++++++++++++++- diff --git a/upstream_utils/llvm_patches/0013-EpochTracker-ABI-macro.patch b/upstream_utils/llvm_patches/0013-EpochTracker-ABI-macro.patch index d142b8e81a7..7f74ecd9375 100644 --- a/upstream_utils/llvm_patches/0013-EpochTracker-ABI-macro.patch +++ b/upstream_utils/llvm_patches/0013-EpochTracker-ABI-macro.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Wed, 4 May 2022 00:01:00 -0400 -Subject: [PATCH 13/36] EpochTracker ABI macro +Subject: [PATCH 13/37] EpochTracker ABI macro --- llvm/include/llvm/ADT/EpochTracker.h | 2 +- diff --git a/upstream_utils/llvm_patches/0014-Delete-numbers-from-MathExtras.patch b/upstream_utils/llvm_patches/0014-Delete-numbers-from-MathExtras.patch index ebf7baf9c71..a896f9b084f 100644 --- a/upstream_utils/llvm_patches/0014-Delete-numbers-from-MathExtras.patch +++ b/upstream_utils/llvm_patches/0014-Delete-numbers-from-MathExtras.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Thu, 5 May 2022 18:09:45 -0400 -Subject: [PATCH 14/36] Delete numbers from MathExtras +Subject: [PATCH 14/37] Delete numbers from MathExtras --- llvm/include/llvm/Support/MathExtras.h | 36 -------------------------- diff --git a/upstream_utils/llvm_patches/0015-Add-lerp-and-sgn.patch b/upstream_utils/llvm_patches/0015-Add-lerp-and-sgn.patch index 92a744d351b..4612f614f2b 100644 --- a/upstream_utils/llvm_patches/0015-Add-lerp-and-sgn.patch +++ b/upstream_utils/llvm_patches/0015-Add-lerp-and-sgn.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Tue, 3 May 2022 22:50:24 -0400 -Subject: [PATCH 15/36] Add lerp and sgn +Subject: [PATCH 15/37] Add lerp and sgn --- llvm/include/llvm/Support/MathExtras.h | 20 ++++++++++++++++++++ diff --git a/upstream_utils/llvm_patches/0016-Fixup-includes.patch b/upstream_utils/llvm_patches/0016-Fixup-includes.patch index faa4f49c780..cf04342f349 100644 --- a/upstream_utils/llvm_patches/0016-Fixup-includes.patch +++ b/upstream_utils/llvm_patches/0016-Fixup-includes.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 16:38:11 -0400 -Subject: [PATCH 16/36] Fixup includes +Subject: [PATCH 16/37] Fixup includes --- llvm/include/llvm/ADT/StringMap.h | 4 ++++ diff --git a/upstream_utils/llvm_patches/0017-Use-std-is_trivially_copy_constructible.patch b/upstream_utils/llvm_patches/0017-Use-std-is_trivially_copy_constructible.patch index 486d887d58e..40adf0eab90 100644 --- a/upstream_utils/llvm_patches/0017-Use-std-is_trivially_copy_constructible.patch +++ b/upstream_utils/llvm_patches/0017-Use-std-is_trivially_copy_constructible.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 16:42:09 -0400 -Subject: [PATCH 17/36] Use std::is_trivially_copy_constructible +Subject: [PATCH 17/37] Use std::is_trivially_copy_constructible --- llvm/include/llvm/Support/type_traits.h | 16 ---------------- diff --git a/upstream_utils/llvm_patches/0018-Windows-support.patch b/upstream_utils/llvm_patches/0018-Windows-support.patch index 15e423509bc..f9793cc69c6 100644 --- a/upstream_utils/llvm_patches/0018-Windows-support.patch +++ b/upstream_utils/llvm_patches/0018-Windows-support.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Tue, 3 May 2022 20:22:38 -0400 -Subject: [PATCH 18/36] Windows support +Subject: [PATCH 18/37] Windows support --- .../llvm/Support/Windows/WindowsSupport.h | 45 +++++---- diff --git a/upstream_utils/llvm_patches/0019-Prefer-fmtlib.patch b/upstream_utils/llvm_patches/0019-Prefer-fmtlib.patch index c2704d278cc..8995a7e32a5 100644 --- a/upstream_utils/llvm_patches/0019-Prefer-fmtlib.patch +++ b/upstream_utils/llvm_patches/0019-Prefer-fmtlib.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 16:46:20 -0400 -Subject: [PATCH 19/36] Prefer fmtlib +Subject: [PATCH 19/37] Prefer fmtlib --- llvm/lib/Support/ErrorHandling.cpp | 20 ++++++-------------- diff --git a/upstream_utils/llvm_patches/0020-Prefer-wpi-s-fs.h.patch b/upstream_utils/llvm_patches/0020-Prefer-wpi-s-fs.h.patch index ad4189436d9..c8a6bd3c813 100644 --- a/upstream_utils/llvm_patches/0020-Prefer-wpi-s-fs.h.patch +++ b/upstream_utils/llvm_patches/0020-Prefer-wpi-s-fs.h.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 16:49:36 -0400 -Subject: [PATCH 20/36] Prefer wpi's fs.h +Subject: [PATCH 20/37] Prefer wpi's fs.h --- llvm/include/llvm/Support/raw_ostream.h | 7 ++----- diff --git a/upstream_utils/llvm_patches/0021-Remove-unused-functions.patch b/upstream_utils/llvm_patches/0021-Remove-unused-functions.patch index c326bc4cbe1..ec263b299ed 100644 --- a/upstream_utils/llvm_patches/0021-Remove-unused-functions.patch +++ b/upstream_utils/llvm_patches/0021-Remove-unused-functions.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 19:16:51 -0400 -Subject: [PATCH 21/36] Remove unused functions +Subject: [PATCH 21/37] Remove unused functions --- llvm/include/llvm/Support/raw_ostream.h | 5 +- diff --git a/upstream_utils/llvm_patches/0022-OS-specific-changes.patch b/upstream_utils/llvm_patches/0022-OS-specific-changes.patch index 91f1302b168..1f0d6112673 100644 --- a/upstream_utils/llvm_patches/0022-OS-specific-changes.patch +++ b/upstream_utils/llvm_patches/0022-OS-specific-changes.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 19:30:43 -0400 -Subject: [PATCH 22/36] OS-specific changes +Subject: [PATCH 22/37] OS-specific changes --- llvm/lib/Support/ErrorHandling.cpp | 16 +++++++--------- diff --git a/upstream_utils/llvm_patches/0023-Use-SmallVector-for-UTF-conversion.patch b/upstream_utils/llvm_patches/0023-Use-SmallVector-for-UTF-conversion.patch index bb096a2b05f..84fc17c40b7 100644 --- a/upstream_utils/llvm_patches/0023-Use-SmallVector-for-UTF-conversion.patch +++ b/upstream_utils/llvm_patches/0023-Use-SmallVector-for-UTF-conversion.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Mon, 9 May 2022 00:04:30 -0400 -Subject: [PATCH 23/36] Use SmallVector for UTF conversion +Subject: [PATCH 23/37] Use SmallVector for UTF conversion --- llvm/include/llvm/Support/ConvertUTF.h | 6 +++--- diff --git a/upstream_utils/llvm_patches/0024-Prefer-to-use-static-pointers-in-raw_ostream.patch b/upstream_utils/llvm_patches/0024-Prefer-to-use-static-pointers-in-raw_ostream.patch index ecab45a58bd..d37d60d4dd3 100644 --- a/upstream_utils/llvm_patches/0024-Prefer-to-use-static-pointers-in-raw_ostream.patch +++ b/upstream_utils/llvm_patches/0024-Prefer-to-use-static-pointers-in-raw_ostream.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Thu, 19 May 2022 00:58:36 -0400 -Subject: [PATCH 24/36] Prefer to use static pointers in raw_ostream +Subject: [PATCH 24/37] Prefer to use static pointers in raw_ostream See #1401 --- diff --git a/upstream_utils/llvm_patches/0025-constexpr-endian-byte-swap.patch b/upstream_utils/llvm_patches/0025-constexpr-endian-byte-swap.patch index 5b13f98db01..2770541a963 100644 --- a/upstream_utils/llvm_patches/0025-constexpr-endian-byte-swap.patch +++ b/upstream_utils/llvm_patches/0025-constexpr-endian-byte-swap.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Fri, 1 Mar 2024 11:56:17 -0800 -Subject: [PATCH 25/36] constexpr endian byte swap +Subject: [PATCH 25/37] constexpr endian byte swap --- llvm/include/llvm/Support/Endian.h | 4 +++- diff --git a/upstream_utils/llvm_patches/0026-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch b/upstream_utils/llvm_patches/0026-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch index 28831db7bc6..13bb23fde53 100644 --- a/upstream_utils/llvm_patches/0026-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch +++ b/upstream_utils/llvm_patches/0026-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Wed, 10 Aug 2022 17:07:52 -0700 -Subject: [PATCH 26/36] Copy type traits from STLExtras.h into PointerUnion.h +Subject: [PATCH 26/37] Copy type traits from STLExtras.h into PointerUnion.h --- llvm/include/llvm/ADT/PointerUnion.h | 46 ++++++++++++++++++++++++++++ diff --git a/upstream_utils/llvm_patches/0027-Remove-StringMap-test-for-llvm-sort.patch b/upstream_utils/llvm_patches/0027-Remove-StringMap-test-for-llvm-sort.patch index a6356bfd6ac..f238466956d 100644 --- a/upstream_utils/llvm_patches/0027-Remove-StringMap-test-for-llvm-sort.patch +++ b/upstream_utils/llvm_patches/0027-Remove-StringMap-test-for-llvm-sort.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Wed, 10 Aug 2022 22:35:00 -0700 -Subject: [PATCH 27/36] Remove StringMap test for llvm::sort() +Subject: [PATCH 27/37] Remove StringMap test for llvm::sort() --- llvm/unittests/ADT/StringMapTest.cpp | 14 -------------- diff --git a/upstream_utils/llvm_patches/0028-Unused-variable-in-release-mode.patch b/upstream_utils/llvm_patches/0028-Unused-variable-in-release-mode.patch index 3841f9d7068..3cbe6ff2c5f 100644 --- a/upstream_utils/llvm_patches/0028-Unused-variable-in-release-mode.patch +++ b/upstream_utils/llvm_patches/0028-Unused-variable-in-release-mode.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Leander Schulten Date: Mon, 10 Jul 2023 00:53:43 +0200 -Subject: [PATCH 28/36] Unused variable in release mode +Subject: [PATCH 28/37] Unused variable in release mode --- llvm/include/llvm/ADT/DenseMap.h | 2 +- diff --git a/upstream_utils/llvm_patches/0029-Use-C-20-bit-header.patch b/upstream_utils/llvm_patches/0029-Use-C-20-bit-header.patch index a0c7919f458..567fa7f7b74 100644 --- a/upstream_utils/llvm_patches/0029-Use-C-20-bit-header.patch +++ b/upstream_utils/llvm_patches/0029-Use-C-20-bit-header.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 11 Jul 2023 22:56:09 -0700 -Subject: [PATCH 29/36] Use C++20 header +Subject: [PATCH 29/37] Use C++20 header --- llvm/include/llvm/ADT/DenseMap.h | 3 +- diff --git a/upstream_utils/llvm_patches/0030-Remove-DenseMap-GTest-printer-test.patch b/upstream_utils/llvm_patches/0030-Remove-DenseMap-GTest-printer-test.patch index b3cdfa81b17..8cf920d2752 100644 --- a/upstream_utils/llvm_patches/0030-Remove-DenseMap-GTest-printer-test.patch +++ b/upstream_utils/llvm_patches/0030-Remove-DenseMap-GTest-printer-test.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sun, 30 Jul 2023 14:17:37 -0700 -Subject: [PATCH 30/36] Remove DenseMap GTest printer test +Subject: [PATCH 30/37] Remove DenseMap GTest printer test LLVM modifies internal GTest headers to support it, which we can't do. --- diff --git a/upstream_utils/llvm_patches/0031-Replace-deprecated-std-aligned_storage_t.patch b/upstream_utils/llvm_patches/0031-Replace-deprecated-std-aligned_storage_t.patch index b68a78e4dd0..e31e52869ed 100644 --- a/upstream_utils/llvm_patches/0031-Replace-deprecated-std-aligned_storage_t.patch +++ b/upstream_utils/llvm_patches/0031-Replace-deprecated-std-aligned_storage_t.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Fri, 15 Sep 2023 18:26:50 -0700 -Subject: [PATCH 31/36] Replace deprecated std::aligned_storage_t +Subject: [PATCH 31/37] Replace deprecated std::aligned_storage_t --- llvm/include/llvm/ADT/FunctionExtras.h | 4 ++-- diff --git a/upstream_utils/llvm_patches/0032-raw_ostream-Add-SetNumBytesInBuffer.patch b/upstream_utils/llvm_patches/0032-raw_ostream-Add-SetNumBytesInBuffer.patch index db3c34e670f..f90c64d2762 100644 --- a/upstream_utils/llvm_patches/0032-raw_ostream-Add-SetNumBytesInBuffer.patch +++ b/upstream_utils/llvm_patches/0032-raw_ostream-Add-SetNumBytesInBuffer.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Sun, 29 Oct 2023 23:00:08 -0700 -Subject: [PATCH 32/36] raw_ostream: Add SetNumBytesInBuffer +Subject: [PATCH 32/37] raw_ostream: Add SetNumBytesInBuffer --- llvm/include/llvm/Support/raw_ostream.h | 5 +++++ diff --git a/upstream_utils/llvm_patches/0033-type_traits.h-Add-is_constexpr.patch b/upstream_utils/llvm_patches/0033-type_traits.h-Add-is_constexpr.patch index 1b2497e7d66..51d178286f0 100644 --- a/upstream_utils/llvm_patches/0033-type_traits.h-Add-is_constexpr.patch +++ b/upstream_utils/llvm_patches/0033-type_traits.h-Add-is_constexpr.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Sat, 2 Dec 2023 15:21:32 -0800 -Subject: [PATCH 33/36] type_traits.h: Add is_constexpr() +Subject: [PATCH 33/37] type_traits.h: Add is_constexpr() --- llvm/include/llvm/Support/type_traits.h | 5 +++++ diff --git a/upstream_utils/llvm_patches/0034-Add-back-removed-raw_string_ostream-write_impl.patch b/upstream_utils/llvm_patches/0034-Add-back-removed-raw_string_ostream-write_impl.patch index ff650b7f290..fe5a59cae64 100644 --- a/upstream_utils/llvm_patches/0034-Add-back-removed-raw_string_ostream-write_impl.patch +++ b/upstream_utils/llvm_patches/0034-Add-back-removed-raw_string_ostream-write_impl.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Fri, 1 Mar 2024 11:37:36 -0800 -Subject: [PATCH 34/36] Add back removed raw_string_ostream::write_impl() +Subject: [PATCH 34/37] Add back removed raw_string_ostream::write_impl() --- llvm/lib/Support/raw_ostream.cpp | 8 ++++++++ diff --git a/upstream_utils/llvm_patches/0035-Remove-auto-conversion-from-raw_ostream.patch b/upstream_utils/llvm_patches/0035-Remove-auto-conversion-from-raw_ostream.patch index df8bd0aefab..5487edc3aef 100644 --- a/upstream_utils/llvm_patches/0035-Remove-auto-conversion-from-raw_ostream.patch +++ b/upstream_utils/llvm_patches/0035-Remove-auto-conversion-from-raw_ostream.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sun, 17 Mar 2024 14:51:11 -0700 -Subject: [PATCH 35/36] Remove auto-conversion from raw_ostream +Subject: [PATCH 35/37] Remove auto-conversion from raw_ostream --- llvm/lib/Support/raw_ostream.cpp | 9 --------- diff --git a/upstream_utils/llvm_patches/0036-Add-SmallVector-erase_if.patch b/upstream_utils/llvm_patches/0036-Add-SmallVector-erase_if.patch index 78bb7ee6293..8bff0003604 100644 --- a/upstream_utils/llvm_patches/0036-Add-SmallVector-erase_if.patch +++ b/upstream_utils/llvm_patches/0036-Add-SmallVector-erase_if.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 18 Jun 2024 09:07:33 -0700 -Subject: [PATCH 36/36] Add SmallVector erase_if() +Subject: [PATCH 36/37] Add SmallVector erase_if() --- llvm/include/llvm/ADT/SmallVector.h | 8 ++++++++ diff --git a/upstream_utils/llvm_patches/0037-Fix-AlignedCharArrayUnion-for-C-23.patch b/upstream_utils/llvm_patches/0037-Fix-AlignedCharArrayUnion-for-C-23.patch new file mode 100644 index 00000000000..a0a25ce8033 --- /dev/null +++ b/upstream_utils/llvm_patches/0037-Fix-AlignedCharArrayUnion-for-C-23.patch @@ -0,0 +1,39 @@ +From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 +From: Tyler Veness +Date: Sat, 13 Jul 2024 15:24:30 -0700 +Subject: [PATCH 37/37] Fix AlignedCharArrayUnion for C++23 + +--- + llvm/include/llvm/Support/AlignOf.h | 14 +++++--------- + 1 file changed, 5 insertions(+), 9 deletions(-) + +diff --git a/llvm/include/llvm/Support/AlignOf.h b/llvm/include/llvm/Support/AlignOf.h +index f586d7f182aab6e56b7fae6ae98a7cd89e63976c..ca98a564733a07a5e16122d31805e970bf76b673 100644 +--- a/llvm/include/llvm/Support/AlignOf.h ++++ b/llvm/include/llvm/Support/AlignOf.h +@@ -13,20 +13,16 @@ + #ifndef LLVM_SUPPORT_ALIGNOF_H + #define LLVM_SUPPORT_ALIGNOF_H + +-#include ++#include ++#include + + namespace llvm { + + /// A suitably aligned and sized character array member which can hold elements + /// of any type. +-/// +-/// This template is equivalent to std::aligned_union_t<1, ...>, but we cannot +-/// use it due to a bug in the MSVC x86 compiler: +-/// https://github.com/microsoft/STL/issues/1533 +-/// Using `alignas` here works around the bug. +-template struct AlignedCharArrayUnion { +- using AlignedUnion = std::aligned_union_t<1, T, Ts...>; +- alignas(alignof(AlignedUnion)) char buffer[sizeof(AlignedUnion)]; ++template struct AlignedCharArrayUnion { ++ alignas((std::max)({alignof(Ts)...})) ++ std::byte buffer[(std::max)({static_cast(1), sizeof(Ts)...})]; + }; + + } // end namespace llvm diff --git a/upstream_utils/update_llvm.py b/upstream_utils/update_llvm.py index 9180442a631..d2d3c379df6 100755 --- a/upstream_utils/update_llvm.py +++ b/upstream_utils/update_llvm.py @@ -214,6 +214,7 @@ def main(): "0034-Add-back-removed-raw_string_ostream-write_impl.patch", "0035-Remove-auto-conversion-from-raw_ostream.patch", "0036-Add-SmallVector-erase_if.patch", + "0037-Fix-AlignedCharArrayUnion-for-C-23.patch", ]: git_am( os.path.join(wpilib_root, "upstream_utils/llvm_patches", f), diff --git a/wpiutil/src/main/native/thirdparty/llvm/include/wpi/AlignOf.h b/wpiutil/src/main/native/thirdparty/llvm/include/wpi/AlignOf.h index 5d400e48071..515455c96d0 100644 --- a/wpiutil/src/main/native/thirdparty/llvm/include/wpi/AlignOf.h +++ b/wpiutil/src/main/native/thirdparty/llvm/include/wpi/AlignOf.h @@ -13,20 +13,16 @@ #ifndef WPIUTIL_WPI_ALIGNOF_H #define WPIUTIL_WPI_ALIGNOF_H -#include +#include +#include namespace wpi { /// A suitably aligned and sized character array member which can hold elements /// of any type. -/// -/// This template is equivalent to std::aligned_union_t<1, ...>, but we cannot -/// use it due to a bug in the MSVC x86 compiler: -/// https://github.com/microsoft/STL/issues/1533 -/// Using `alignas` here works around the bug. -template struct AlignedCharArrayUnion { - using AlignedUnion = std::aligned_union_t<1, T, Ts...>; - alignas(alignof(AlignedUnion)) char buffer[sizeof(AlignedUnion)]; +template struct AlignedCharArrayUnion { + alignas((std::max)({alignof(Ts)...})) + std::byte buffer[(std::max)({static_cast(1), sizeof(Ts)...})]; }; } // end namespace wpi From fc57f6a560df94be3d367cd45ee387ffe429d6e5 Mon Sep 17 00:00:00 2001 From: sciencewhiz Date: Mon, 15 Jul 2024 14:51:10 -0700 Subject: [PATCH 15/20] [ci] Filter python commands comment only for Java sources (#6832) Co-authored-by: David Vo --- .github/workflows/command-robotpy-pr.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/command-robotpy-pr.yml b/.github/workflows/command-robotpy-pr.yml index 7fa28eec1c5..2ba4d6b07fc 100644 --- a/.github/workflows/command-robotpy-pr.yml +++ b/.github/workflows/command-robotpy-pr.yml @@ -5,7 +5,7 @@ on: types: - opened paths: - - 'wpilibNewCommands/**' + - 'wpilibNewCommands/src/**/*.java' jobs: comment: From 9703142ebe926f320f5e339d094dfe541a99bafb Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Mon, 15 Jul 2024 18:12:41 -0400 Subject: [PATCH 16/20] [build] CMake: simplify source JAR creation and install (#6831) Bump required minimum CMake version to 3.21. --- CMakeLists.txt | 2 +- apriltag/CMakeLists.txt | 16 +++---- cameraserver/CMakeLists.txt | 15 +++---- cmake/modules/CreateSourceJar.cmake | 34 +++++++++++++++ cscore/CMakeLists.txt | 15 +++---- hal/CMakeLists.txt | 24 +++-------- ntcore/CMakeLists.txt | 19 +++------ romiVendordep/CMakeLists.txt | 13 +++--- wpilibNewCommands/CMakeLists.txt | 21 +++------ wpilibj/CMakeLists.txt | 66 +++++++++-------------------- wpimath/CMakeLists.txt | 48 +++------------------ wpinet/CMakeLists.txt | 13 +++--- wpiunits/CMakeLists.txt | 13 ++++++ wpiutil/CMakeLists.txt | 23 +++------- xrpVendordep/CMakeLists.txt | 13 +++--- 15 files changed, 131 insertions(+), 204 deletions(-) create mode 100644 cmake/modules/CreateSourceJar.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index 957114d2805..ba4eba9029b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -15,7 +15,7 @@ if("${CMAKE_HOST_SYSTEM_NAME}" STREQUAL "Windows") message(STATUS "Platform version: ${CMAKE_VS_WINDOWS_TARGET_PLATFORM_VERSION}") endif() -cmake_minimum_required(VERSION 3.11) +cmake_minimum_required(VERSION 3.21) project(allwpilib) set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_SOURCE_DIR}/cmake/modules") diff --git a/apriltag/CMakeLists.txt b/apriltag/CMakeLists.txt index 9be0eaa2675..72360354491 100644 --- a/apriltag/CMakeLists.txt +++ b/apriltag/CMakeLists.txt @@ -87,22 +87,16 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file(GLOB APRILTAG_SOURCES src/main/java/edu/wpi/first/apriltag/*.java) - add_jar( + include(CreateSourceJar) + add_source_jar( apriltag_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/apriltag" ${APRILTAG_SOURCES} - NAMESPACE - "edu/wpi/first/apriltag/jni" - src/main/java/edu/wpi/first/apriltag/jni/AprilTagJNI.java + BASE_DIRECTORIES ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java OUTPUT_NAME apriltag-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(APRILTAG_SRC_JAR_FILE TARGET apriltag_src_jar PROPERTY JAR_FILE) - install(FILES ${APRILTAG_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET apriltag_src_jar PROPERTY FOLDER "java") + + install_jar(apriltag_src_jar DESTINATION ${java_lib_dest}) endif() generate_resources( diff --git a/cameraserver/CMakeLists.txt b/cameraserver/CMakeLists.txt index 2ea645470e2..3b04c94bba1 100644 --- a/cameraserver/CMakeLists.txt +++ b/cameraserver/CMakeLists.txt @@ -42,21 +42,16 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file(GLOB CAMERASERVER_SOURCES src/main/java/edu/wpi/first/cameraserver/*.java) - file(GLOB VISION_SOURCES src/main/java/edu/wpi/first/vision/*.java) - add_jar( + include(CreateSourceJar) + add_source_jar( cameraserver_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/cameraserver" ${CAMERASERVER_SOURCES} - NAMESPACE "edu/wpi/first/vision" ${VISION_SOURCES} + BASE_DIRECTORIES ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java OUTPUT_NAME cameraserver-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(CAMERASERVER_SRC_JAR_FILE TARGET cameraserver_src_jar PROPERTY JAR_FILE) - install(FILES ${CAMERASERVER_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET cameraserver_src_jar PROPERTY FOLDER "java") + + install_jar(cameraserver_src_jar DESTINATION ${java_lib_dest}) endif() file(GLOB_RECURSE cameraserver_native_src src/main/native/cpp/*.cpp) diff --git a/cmake/modules/CreateSourceJar.cmake b/cmake/modules/CreateSourceJar.cmake new file mode 100644 index 00000000000..cb83866eb85 --- /dev/null +++ b/cmake/modules/CreateSourceJar.cmake @@ -0,0 +1,34 @@ +macro(add_source_jar target) + set(oneValueArgs OUTPUT_NAME OUTPUT_DIR) + cmake_parse_arguments(SOURCE_JAR "" "${oneValueArgs}" "BASE_DIRECTORIES" ${ARGN}) + foreach(base_package_dir ${SOURCE_JAR_BASE_DIRECTORIES}) + file(GLOB_RECURSE directories LIST_DIRECTORIES true ${base_package_dir}/*.directoriesonly) + # Find all packages + foreach(directory ${directories}) + cmake_path( + RELATIVE_PATH + directory + BASE_DIRECTORY ${base_package_dir} + OUTPUT_VARIABLE package_name + ) + file(GLOB package_sources ${directory}/*.java) + if(package_sources STREQUAL "") + continue() + endif() + # If package sources are scattered across different places, consolidate them under one package + list(FIND packages ${package_name} index) + if(index EQUAL -1) + list(APPEND packages ${package_name}) + endif() + list(APPEND ${package_name} ${package_sources}) + endforeach() + endforeach() + set(resources "") + foreach(package ${packages}) + string(APPEND resources "NAMESPACE \"${package}\" ${${package}} ") + endforeach() + cmake_language( + EVAL CODE + "add_jar(${target} RESOURCES ${resources} OUTPUT_NAME ${SOURCE_JAR_OUTPUT_NAME} OUTPUT_DIR ${SOURCE_JAR_OUTPUT_DIR})" + ) +endmacro() diff --git a/cscore/CMakeLists.txt b/cscore/CMakeLists.txt index 24b605e9026..8bc10478d4a 100644 --- a/cscore/CMakeLists.txt +++ b/cscore/CMakeLists.txt @@ -129,21 +129,16 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file(GLOB CSCORE_SOURCES src/main/java/edu/wpi/first/cscore/*.java) - file(GLOB CSCORE_RAW_SOURCES src/main/java/edu/wpi/first/cscore/raw/*.java) - add_jar( + include(CreateSourceJar) + add_source_jar( cscore_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/cscore" ${CSCORE_SOURCES} - NAMESPACE "edu/wpi/first/cscore/raw" ${CSCORE_RAW_SOURCES} + BASE_DIRECTORIES ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java OUTPUT_NAME cscore-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(CSCORE_SRC_JAR_FILE TARGET cscore_src_jar PROPERTY JAR_FILE) - install(FILES ${CSCORE_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET cscore_src_jar PROPERTY FOLDER "java") + + install_jar(cscore_src_jar DESTINATION ${java_lib_dest}) endif() if(WITH_TESTS) diff --git a/hal/CMakeLists.txt b/hal/CMakeLists.txt index 31f640cec8a..1b8c49b4c80 100644 --- a/hal/CMakeLists.txt +++ b/hal/CMakeLists.txt @@ -80,28 +80,18 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file(GLOB HAL_SOURCES src/main/java/edu/wpi/first/hal/*.java src/generated/main/java/*.java) - file(GLOB HAL_CAN_SOURCES src/main/java/edu/wpi/first/hal/can/*.java) - file(GLOB HAL_SIMULATION_SOURCES src/main/java/edu/wpi/first/hal/simulation/*.java) - file(GLOB HAL_UTIL_SOURCES src/main/java/edu/wpi/first/hal/util/*.java) - add_jar( + include(CreateSourceJar) + add_source_jar( hal_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/hal" ${HAL_SOURCES} - NAMESPACE "edu/wpi/first/hal/can" ${HAL_CAN_SOURCES} - NAMESPACE - "edu/wpi/first/hal/communication" - src/main/java/edu/wpi/first/hal/communication/NIRioStatus.java - NAMESPACE "edu/wpi/first/hal/simulation" ${HAL_SIMULATION_SOURCES} - NAMESPACE "edu/wpi/first/hal/util" ${HAL_UTIL_SOURCES} + BASE_DIRECTORIES + ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java + ${CMAKE_CURRENT_SOURCE_DIR}/src/generated/main/java OUTPUT_NAME wpiHal-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(HAL_SRC_JAR_FILE TARGET hal_src_jar PROPERTY JAR_FILE) - install(FILES ${HAL_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET hal_src_jar PROPERTY FOLDER "java") + + install_jar(hal_src_jar DESTINATION ${java_lib_dest}) endif() if(WITH_TESTS) diff --git a/ntcore/CMakeLists.txt b/ntcore/CMakeLists.txt index 101307886df..ab4cc08d7ec 100644 --- a/ntcore/CMakeLists.txt +++ b/ntcore/CMakeLists.txt @@ -76,23 +76,18 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file( - GLOB NTCORE_SOURCES - src/main/java/edu/wpi/first/networktables/*.java - src/generated/main/java/*.java - ) - add_jar( + include(CreateSourceJar) + add_source_jar( ntcore_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/networktables" ${NTCORE_SOURCES} + BASE_DIRECTORIES + ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java + ${CMAKE_CURRENT_SOURCE_DIR}/src/generated/main/java OUTPUT_NAME ntcore-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(NTCORE_SRC_JAR_FILE TARGET ntcore_src_jar PROPERTY JAR_FILE) - install(FILES ${NTCORE_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET ntcore_src_jar PROPERTY FOLDER "java") + + install_jar(ntcore_src_jar DESTINATION ${java_lib_dest}) endif() add_executable(ntcoredev src/dev/native/cpp/main.cpp) diff --git a/romiVendordep/CMakeLists.txt b/romiVendordep/CMakeLists.txt index cae07076089..9cadf9c6553 100644 --- a/romiVendordep/CMakeLists.txt +++ b/romiVendordep/CMakeLists.txt @@ -35,19 +35,16 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file(GLOB_RECURSE ROMIVENDORDEP_SOURCES src/main/java/*.java) - add_jar( + include(CreateSourceJar) + add_source_jar( romiVendordep_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/wpilibj/romi" ${ROMIVENDORDEP_SOURCES} + BASE_DIRECTORIES ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java OUTPUT_NAME romiVendordep-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(ROMIVENDORDEP_SRC_JAR_FILE TARGET romiVendordep_src_jar PROPERTY JAR_FILE) - install(FILES ${ROMIVENDORDEP_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET romiVendordep_src_jar PROPERTY FOLDER "java") + + install_jar(romiVendordep_src_jar DESTINATION ${java_lib_dest}) endif() file(GLOB_RECURSE romiVendordep_native_src src/main/native/cpp/*.cpp) diff --git a/wpilibNewCommands/CMakeLists.txt b/wpilibNewCommands/CMakeLists.txt index 43292dfbe47..ea13d68d477 100644 --- a/wpilibNewCommands/CMakeLists.txt +++ b/wpilibNewCommands/CMakeLists.txt @@ -37,25 +37,18 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file(GLOB WPILIBNEWCOMMANDS_SOURCES src/main/java/edu/wpi/first/wpilibj2/command/*.java) - file( - GLOB WPILIBNEWCOMMANDS_BUTTON_SOURCES - src/main/java/edu/wpi/first/wpilibj2/command/button/*.java - src/generated/main/java/edu/wpi/first/wpilibj2/command/button/*.java - ) - add_jar( + include(CreateSourceJar) + add_source_jar( wpilibNewCommands_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/wpilibj2/command" ${WPILIBNEWCOMMANDS_SOURCES} - NAMESPACE "edu/wpi/first/wpilibj2/command/button" ${WPILIBNEWCOMMANDS_BUTTON_SOURCES} + BASE_DIRECTORIES + ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java + ${CMAKE_CURRENT_SOURCE_DIR}/src/generated/main/java OUTPUT_NAME wpilibNewCommands-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(WPILIBNEWCOMMANDS_SRC_JAR_FILE TARGET wpilibNewCommands_src_jar PROPERTY JAR_FILE) - install(FILES ${WPILIBNEWCOMMANDS_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET wpilibNewCommands_src_jar PROPERTY FOLDER "java") + + install_jar(wpilibNewCommands_src_jar DESTINATION ${java_lib_dest}) endif() file( diff --git a/wpilibj/CMakeLists.txt b/wpilibj/CMakeLists.txt index 6124368075f..440f7585592 100644 --- a/wpilibj/CMakeLists.txt +++ b/wpilibj/CMakeLists.txt @@ -17,7 +17,10 @@ if(WITH_JAVA) NO_DEFAULT_PATH ) - configure_file(src/generate/WPILibVersion.java.in WPILibVersion.java) + configure_file( + src/generate/WPILibVersion.java.in + generated/main/java/edu/wpi/first/wpilibj/WPILibVersion.java + ) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java src/generated/main/java/*.java) file(GLOB EJML_JARS "${WPILIB_BINARY_DIR}/wpimath/thirdparty/ejml/*.jar") @@ -26,7 +29,7 @@ if(WITH_JAVA) add_jar( wpilibj_jar ${JAVA_SOURCES} - ${CMAKE_CURRENT_BINARY_DIR}/WPILibVersion.java + ${CMAKE_CURRENT_BINARY_DIR}/generated/main/java/edu/wpi/first/wpilibj/WPILibVersion.java INCLUDE_JARS hal_jar ntcore_jar @@ -51,53 +54,24 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file( - GLOB WPILIBJ_SOURCES - src/main/java/edu/wpi/first/wpilibj/*.java - src/generated/main/java/edu/wpi/first/wpilibj/*.java - ) - file(GLOB WPILIBJ_COUNTER_SOURCES src/main/java/edu/wpi/first/wpilibj/counter/*.java) - file(GLOB WPILIBJ_DRIVE_SOURCES src/main/java/edu/wpi/first/wpilibj/drive/*.java) - file(GLOB WPILIBJ_EVENT_SOURCES src/main/java/edu/wpi/first/wpilibj/event/*.java) - file(GLOB WPILIBJ_INTERFACES_SOURCES src/main/java/edu/wpi/first/wpilibj/interfaces/*.java) - file(GLOB WPILIBJ_MOTORCONTROL_SOURCES src/main/java/edu/wpi/first/wpilibj/motorcontrol*.java) - file(GLOB WPILIBJ_SHUFFLEBOARD_SOURCES src/main/java/edu/wpi/first/wpilibj/shuffleboard*.java) - file( - GLOB WPILIBJ_SIMULATION_SOURCES - src/main/java/edu/wpi/first/wpilibj/simulation/*.java - src/generated/main/java/edu/wpi/first/wpilibj/simulation/*.java - ) - file(GLOB WPILIBJ_SMARTDASHBOARD_SOURCES src/main/java/edu/wpi/first/wpilibj/*.java) - file( - GLOB WPILIBJ_UTIL_SOURCES - src/main/java/edu/wpi/first/wpilibj/*.java - ${CMAKE_CURRENT_BINARY_DIR}/WPILibVersion.java - ) - add_jar( + include(CreateSourceJar) + # Generate version file if it wasn't generated already + if(NOT WITH_JAVA) + configure_file( + src/generate/WPILi1bVersion.java.in + generated/main/java/edu/wpi/first/wpilibj/WPILibVersion.java + ) + endif() + add_source_jar( wpilibj_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/wpilibj" ${WPILIBJ_SOURCES} - NAMESPACE "edu/wpi/first/wpilibj/counter" ${WPILIBJ_COUNTER_SOURCES} - NAMESPACE "edu/wpi/first/wpilibj/drive" ${WPILIBJ_DRIVE_SOURCES} - NAMESPACE "edu/wpi/first/wpilibj/event" ${WPILIBJ_EVENT_SOURCES} - NAMESPACE "edu/wpi/first/wpilibj/interfaces" ${WPILIBJ_INTERFACES_SOURCES} - NAMESPACE - "edu/wpi/first/wpilibj/internal" - src/main/java/edu/wpi/first/wpilibj/internal/DriverStationModeThread.java - NAMESPACE - "edu/wpi/first/wpilibj/livewindow" - src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java - NAMESPACE "edu/wpi/first/wpilibj/motorcontrol" ${WPILIBJ_MOTORCONTROL_SOURCES} - NAMESPACE "edu/wpi/first/wpilibj/shuffleboard" ${WPILIBJ_SHUFFLEBOARD_SOURCES} - NAMESPACE "edu/wpi/first/wpilibj/simulation" ${WPILIBJ_SIMULATION_SOURCES} - NAMESPACE "edu/wpi/first/wpilibj/smartdashboard" ${WPILIBJ_SMARTDASHBOARD_SOURCES} - NAMESPACE "edu/wpi/first/wpilibj/util" ${WPILIBJ_UTIL_SOURCES} + BASE_DIRECTORIES + ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java + ${CMAKE_CURRENT_SOURCE_DIR}/src/generated/main/java + ${CMAKE_CURRENT_BINARY_DIR}/generated/main/java OUTPUT_NAME wpilibj-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(WPILIBJ_SRC_JAR_FILE TARGET wpilibj_src_jar PROPERTY JAR_FILE) - install(FILES ${WPILIBJ_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET wpilibj_src_jar PROPERTY FOLDER "java") + + install_jar(wpilibj_src_jar DESTINATION ${java_lib_dest}) endif() diff --git a/wpimath/CMakeLists.txt b/wpimath/CMakeLists.txt index 80ed18d40cd..39473631a40 100644 --- a/wpimath/CMakeLists.txt +++ b/wpimath/CMakeLists.txt @@ -107,52 +107,18 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file( - GLOB WPIMATH_SOURCES - src/main/java/edu/wpi/first/math/*.java - src/generated/main/java/edu/wpi/first/math/Nat.java - ) - file(GLOB WPIMATH_CONTROLLER_SOURCES src/main/java/edu/wpi/first/math/controller/*.java) - file(GLOB WPIMATH_ESTIMATOR_SOURCES src/main/java/edu/wpi/first/math/estimator/*.java) - file(GLOB WPIMATH_FILTER_SOURCES src/main/java/edu/wpi/first/math/filter/*.java) - file(GLOB WPIMATH_GEOMETRY_SOURCES src/main/java/edu/wpi/first/math/geometry/*.java) - file(GLOB WPIMATH_INTERPOLATION_SOURCES src/main/java/edu/wpi/first/math/interpolation/*.java) - file(GLOB WPIMATH_KINEMATICS_SOURCES src/main/java/edu/wpi/first/math/kinematics/*.java) - file(GLOB WPIMATH_NUMBERS_SOURCES src/generated/main/java/edu/wpi/first/math/numbers/*.java) - file(GLOB WPIMATH_SPLINE_SOURCES src/main/java/edu/wpi/first/math/spline/*.java) - file(GLOB WPIMATH_SYSTEM_SOURCES src/main/java/edu/wpi/first/math/system/*.java) - file(GLOB WPIMATH_SYSTEM_PLANT_SOURCES src/main/java/edu/wpi/first/math/system/plant/*.java) - file(GLOB WPIMATH_TRAJECTORY_SOURCES src/main/java/edu/wpi/first/math/trajectory/*.java) - file( - GLOB WPIMATH_TRAJECTORY_CONSTRAINT_SOURCES - src/main/java/edu/wpi/first/math/trajectory/constraint/*.java - ) - add_jar( + include(CreateSourceJar) + add_source_jar( wpimath_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/math" ${WPIMATH_SOURCES} - NAMESPACE "edu/wpi/first/math/controller" ${WPIMATH_CONTROLLER_SOURCES} - NAMESPACE "edu/wpi/first/math/estimator" ${WPIMATH_ESTIMATOR_SOURCES} - NAMESPACE "edu/wpi/first/math/filter" ${WPIMATH_FILTER_SOURCES} - NAMESPACE "edu/wpi/first/math/geometry" ${WPIMATH_GEOMETRY_SOURCES} - NAMESPACE "edu/wpi/first/math/interpolation" ${WPIMATH_INTERPOLATION_SOURCES} - NAMESPACE "edu/wpi/first/math/kinematics" ${WPIMATH_KINEMATICS_SOURCES} - NAMESPACE "edu/wpi/first/math/spline" ${WPIMATH_SPLINE_SOURCES} - NAMESPACE "edu/wpi/first/math/system" ${WPIMATH_SYSTEM_SOURCES} - NAMESPACE "edu/wpi/first/math/system/plant" ${WPIMATH_SYSTEM_PLANT_SOURCES} - NAMESPACE "edu/wpi/first/math/trajectory" ${WPIMATH_TRAJECTORY_SOURCES} - NAMESPACE - "edu/wpi/first/math/trajectory/constraint" - ${WPIMATH_TRAJECTORY_CONSTRAINT_SOURCES} - NAMESPACE "edu/wpi/first/math/util" src/main/java/edu/wpi/first/math/util/Units.java + BASE_DIRECTORIES + ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java + ${CMAKE_CURRENT_SOURCE_DIR}/src/generated/main/java OUTPUT_NAME wpimath-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(WPIMATH_SRC_JAR_FILE TARGET wpimath_src_jar PROPERTY JAR_FILE) - install(FILES ${WPIMATH_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET wpimath_src_jar PROPERTY FOLDER "java") + + install_jar(wpimath_src_jar DESTINATION ${java_lib_dest}) endif() file( diff --git a/wpinet/CMakeLists.txt b/wpinet/CMakeLists.txt index bddb4db83a9..f978be5cfba 100644 --- a/wpinet/CMakeLists.txt +++ b/wpinet/CMakeLists.txt @@ -43,19 +43,16 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file(GLOB WPINET_SOURCES src/main/java/edu/wpi/first/net/*.java) - add_jar( + include(CreateSourceJar) + add_source_jar( wpinet_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/net" ${WPINET_SOURCES} + BASE_DIRECTORIES ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java OUTPUT_NAME wpinet-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(WPINET_SRC_JAR_FILE TARGET wpinet_src_jar PROPERTY JAR_FILE) - install(FILES ${WPINET_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET wpinet_src_jar PROPERTY FOLDER "java") + + install_jar(wpinet_src_jar DESTINATION ${java_lib_dest}) endif() set(THREADS_PREFER_PTHREAD_FLAG ON) diff --git a/wpiunits/CMakeLists.txt b/wpiunits/CMakeLists.txt index 3cba94bfd63..1bfa329089d 100644 --- a/wpiunits/CMakeLists.txt +++ b/wpiunits/CMakeLists.txt @@ -18,3 +18,16 @@ if(WITH_JAVA) install_jar_exports(TARGETS wpiunits_jar FILE wpiunits.cmake DESTINATION share/wpiunits) install(FILES wpiunits-config.cmake DESTINATION share/wpiunits) endif() + +if(WITH_JAVA_SOURCE) + include(UseJava) + include(CreateSourceJar) + add_source_jar( + wpiunits_src_jar + BASE_DIRECTORIES ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java + OUTPUT_NAME wpiunits-sources + ) + set_property(TARGET wpiunits_src_jar PROPERTY FOLDER "java") + + install_jar(wpiunits_src_jar DESTINATION ${java_lib_dest}) +endif() diff --git a/wpiutil/CMakeLists.txt b/wpiutil/CMakeLists.txt index 3b26931b182..a296a58691c 100644 --- a/wpiutil/CMakeLists.txt +++ b/wpiutil/CMakeLists.txt @@ -87,29 +87,16 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file(GLOB WPIUTIL_SOURCES src/main/java/edu/wpi/first/util/*.java) - file(GLOB WPIUTIL_CLEANUP_SOURCES src/main/java/edu/wpi/first/util/cleanup/*.java) - file(GLOB WPIUTIL_CONCURRENT_SOURCES src/main/java/edu/wpi/first/util/concurrent/*.java) - file(GLOB WPIUTIL_DATALOG_SOURCES src/main/java/edu/wpi/first/util/datalog/*.java) - file(GLOB WPIUTIL_FUNCTION_SOURCES src/main/java/edu/wpi/first/util/function/*.java) - file(GLOB WPIUTIL_SENDABLE_SOURCES src/main/java/edu/wpi/first/util/sendable/*.java) - add_jar( + include(CreateSourceJar) + add_source_jar( wpiutil_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/util" ${WPIUTIL_SOURCES} - NAMESPACE "edu/wpi/first/util/cleanup" ${WPIUTIL_CLEANUP_SOURCES} - NAMESPACE "edu/wpi/first/util/concurrent" ${WPIUTIL_CONCURRENT_SOURCES} - NAMESPACE "edu/wpi/first/util/datalog" ${WPIUTIL_DATALOG_SOURCES} - NAMESPACE "edu/wpi/first/util/function" ${WPIUTIL_FUNCTION_SOURCES} - NAMESPACE "edu/wpi/first/util/sendable" ${WPIUTIL_SENDABLE_SOURCES} + BASE_DIRECTORIES ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java OUTPUT_NAME wpiutil-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(WPIUTIL_SRC_JAR_FILE TARGET wpiutil_src_jar PROPERTY JAR_FILE) - install(FILES ${WPIUTIL_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET wpiutil_src_jar PROPERTY FOLDER "java") + + install_jar(wpiutil_src_jar DESTINATION ${java_lib_dest}) endif() set(THREADS_PREFER_PTHREAD_FLAG ON) diff --git a/xrpVendordep/CMakeLists.txt b/xrpVendordep/CMakeLists.txt index e57c703417a..6229de558c1 100644 --- a/xrpVendordep/CMakeLists.txt +++ b/xrpVendordep/CMakeLists.txt @@ -35,19 +35,16 @@ endif() if(WITH_JAVA_SOURCE) include(UseJava) - file(GLOB XRPVENDORDEP_SOURCES src/main/java/edu/wpi/first/wpilibj/xrp/*.java) - add_jar( + include(CreateSourceJar) + add_source_jar( xrpVendordep_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/wpilibj/xrp" ${XRPVENDORDEP_SOURCES} + BASE_DIRECTORIES ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java OUTPUT_NAME xrpVendordep-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(xrpVendordep_src_JAR_FILE TARGET xrpVendordep_src_jar PROPERTY JAR_FILE) - install(FILES ${xrpVendordep_src_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET xrpVendordep_src_jar PROPERTY FOLDER "java") + + install_jar(xrpVendordep_src_jar DESTINATION ${java_lib_dest}) endif() file(GLOB_RECURSE xrpVendordep_native_src src/main/native/cpp/*.cpp) From 636450ab7b0b19d7531b2d30726ce583beb10cfe Mon Sep 17 00:00:00 2001 From: Ryan Blue Date: Mon, 15 Jul 2024 20:19:07 -0400 Subject: [PATCH 17/20] [build] Disable std::mutex constexpr constructor on Windows (#6791) We will plan to re-enable this after we release an installer with an updated runtime. --- cmake/modules/CompileWarnings.cmake | 5 +++++ shared/config.gradle | 5 +++++ 2 files changed, 10 insertions(+) diff --git a/cmake/modules/CompileWarnings.cmake b/cmake/modules/CompileWarnings.cmake index 94d952ce5d7..432c810ca9b 100644 --- a/cmake/modules/CompileWarnings.cmake +++ b/cmake/modules/CompileWarnings.cmake @@ -54,4 +54,9 @@ macro(wpilib_target_warnings target) ) target_compile_options(${target} PRIVATE -gz=zlib) endif() + + # Disable std::mutex constexpr constructor on MSVC + if(MSVC) + target_compile_options(${target} PRIVATE /D_DISABLE_CONSTEXPR_MUTEX_CONSTRUCTOR) + endif() endmacro() diff --git a/shared/config.gradle b/shared/config.gradle index 6c4f3942b42..1d184295afa 100644 --- a/shared/config.gradle +++ b/shared/config.gradle @@ -41,6 +41,11 @@ nativeUtils.platformConfigs.each { } } +// Disable std::mutex constexpr constructor on MSVC +nativeUtils.platformConfigs.named(nativeUtils.wpi.platforms.windowsx64).configure { + it.cppCompiler.args.add("/D_DISABLE_CONSTEXPR_MUTEX_CONSTRUCTOR") +} + nativeUtils.platformConfigs.linuxathena.linker.args.add("-Wl,--fatal-warnings") model { From 7b7d17ccd79bcf8ff0edda6f54c86cfa0d2aeaf0 Mon Sep 17 00:00:00 2001 From: Joseph Eng <91924258+KangarooKoala@users.noreply.github.com> Date: Mon, 15 Jul 2024 17:19:31 -0700 Subject: [PATCH 18/20] [wpimath] Add and use kinematics.copyInto() (#6789) --- .../math/kinematics/DifferentialDriveKinematics.java | 7 +++++++ .../edu/wpi/first/math/kinematics/Kinematics.java | 9 +++++++++ .../first/math/kinematics/MecanumDriveKinematics.java | 8 ++++++++ .../java/edu/wpi/first/math/kinematics/Odometry.java | 6 +++--- .../first/math/kinematics/SwerveDriveKinematics.java | 11 +++++++++++ .../main/native/include/frc/kinematics/Kinematics.h | 3 ++- 6 files changed, 40 insertions(+), 4 deletions(-) diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java index 8bcb6a74cfa..d67a7816475 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java @@ -120,6 +120,13 @@ public DifferentialDriveWheelPositions copy(DifferentialDriveWheelPositions posi return new DifferentialDriveWheelPositions(positions.leftMeters, positions.rightMeters); } + @Override + public void copyInto( + DifferentialDriveWheelPositions positions, DifferentialDriveWheelPositions output) { + output.leftMeters = positions.leftMeters; + output.rightMeters = positions.rightMeters; + } + @Override public DifferentialDriveWheelPositions interpolate( DifferentialDriveWheelPositions startValue, diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Kinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Kinematics.java index a64c9a20091..307999d6552 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Kinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Kinematics.java @@ -53,4 +53,13 @@ public interface Kinematics extends Interpolator

{ * @return A copy. */ P copy(P positions); + + /** + * Copies the value of the wheel positions object into the output. + * + * @param positions The wheel positions object to copy. Will not be modified. + * @param output The output variable of the copy operation. Will have the same value as the + * positions object after the call. + */ + void copyInto(P positions, P output); } diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java index 4589a448533..26108088c63 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java @@ -266,6 +266,14 @@ public MecanumDriveWheelPositions copy(MecanumDriveWheelPositions positions) { positions.rearRightMeters); } + @Override + public void copyInto(MecanumDriveWheelPositions positions, MecanumDriveWheelPositions output) { + output.frontLeftMeters = positions.frontLeftMeters; + output.frontRightMeters = positions.frontRightMeters; + output.rearLeftMeters = positions.rearLeftMeters; + output.rearRightMeters = positions.rearRightMeters; + } + @Override public MecanumDriveWheelPositions interpolate( MecanumDriveWheelPositions startValue, MecanumDriveWheelPositions endValue, double t) { diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java index 66ce592957d..6a09f92bffd 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java @@ -25,7 +25,7 @@ public class Odometry { private Rotation2d m_gyroOffset; private Rotation2d m_previousAngle; - private T m_previousWheelPositions; + private final T m_previousWheelPositions; /** * Constructs an Odometry object. @@ -61,7 +61,7 @@ public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d poseMet m_poseMeters = poseMeters; m_previousAngle = m_poseMeters.getRotation(); m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle); - m_previousWheelPositions = m_kinematics.copy(wheelPositions); + m_kinematics.copyInto(wheelPositions, m_previousWheelPositions); } /** @@ -122,7 +122,7 @@ public Pose2d update(Rotation2d gyroAngle, T wheelPositions) { var newPose = m_poseMeters.exp(twist); - m_previousWheelPositions = m_kinematics.copy(wheelPositions); + m_kinematics.copyInto(wheelPositions, m_previousWheelPositions); m_previousAngle = angle; m_poseMeters = new Pose2d(newPose.getTranslation(), angle); diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java index 39306d0ac69..a25a2bed7da 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java @@ -392,6 +392,17 @@ public SwerveModulePosition[] copy(SwerveModulePosition[] positions) { return newPositions; } + @Override + public void copyInto(SwerveModulePosition[] positions, SwerveModulePosition[] output) { + if (positions.length != output.length) { + throw new IllegalArgumentException("Inconsistent number of modules!"); + } + for (int i = 0; i < positions.length; ++i) { + output[i].distanceMeters = positions[i].distanceMeters; + output[i].angle = positions[i].angle; + } + } + @Override public SwerveModulePosition[] interpolate( SwerveModulePosition[] startValue, SwerveModulePosition[] endValue, double t) { diff --git a/wpimath/src/main/native/include/frc/kinematics/Kinematics.h b/wpimath/src/main/native/include/frc/kinematics/Kinematics.h index 181c9a0abbe..f683dffa943 100644 --- a/wpimath/src/main/native/include/frc/kinematics/Kinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/Kinematics.h @@ -20,7 +20,8 @@ namespace frc { * forward kinematics converts wheel speeds into chassis speed. */ template - requires std::copy_constructible + requires std::copy_constructible && + std::assignable_from class WPILIB_DLLEXPORT Kinematics { public: /** From cd6b70af0e567fb8f070666564b8f81a24e9a15e Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Mon, 15 Jul 2024 20:26:25 -0400 Subject: [PATCH 19/20] [docs] Add documentation for simulation extensions (#6729) --- simulation/README.md | 46 +++++++++++++++++++++++++++ simulation/halsim_ds_socket/README.md | 6 ++++ 2 files changed, 52 insertions(+) create mode 100644 simulation/README.md create mode 100644 simulation/halsim_ds_socket/README.md diff --git a/simulation/README.md b/simulation/README.md new file mode 100644 index 00000000000..7d2c40e69e0 --- /dev/null +++ b/simulation/README.md @@ -0,0 +1,46 @@ +# Simulation Extensions +This is where WPILib's simulation extensions are housed. Simulation extensions are referred to by various names: simulation plugins, simulation modules, sim extensions, HALSIM extensions, but they all refer to the same thing, which are dynamically loaded libraries that can use HALSIM functions to register callbacks that update HAL data. The robot program loads simulation extensions by looking for the `HALSIM_EXTENSIONS` environment variable, which contains the paths to the libraries separated by colons on Linux/Mac, and semicolons on Windows. + +# Writing a custom simulation extension +All simulation extensions contain a `int HALSIM_InitExtension(void)` function, which is the entry point. The function declaration should look like this: + +```c++ +extern "C" { +#if defined(WIN32) || defined(_WIN32) +__declspec(dllexport) +#endif +int HALSIM_InitExtension(void) { +} +} +``` + +The function is contained with an `extern "C"` block so it can be called by the robot program and has `__declspec(dllexport)` for Windows. From here, you can interface with the HAL to provide data. + +## Extension registration +Extensions can register themselves by calling `HAL_RegisterExtension`. This will register the extension's name, and a pointer to some sort of data. A separate extension can listen for extension registration by calling `HAL_RegisterExtensionListener`. It takes a callback accepting the data initially passed into `HAL_RegisterExtension`. This can be used to detect if a specific extension was loaded, and take action if it was. Note that extensions must opt-in to registration; extensions that do not register will not trigger the registration listener. + +## Using HALSIM functions +Several devices in the HAL have functions that allow you to feed data from an external source into the HAL. The full list can be found in the HAL subdirectory in `include/hal/simulation`. For example, the AccelerometerData header declares functions that update the X, Y, and Z axes with data. Some functions accept callbacks; the I2CData header declares functions which accept other functions with parameters that allow it to accept data. This allows the implementation of a simulation extension that interfaces with an I2C bus and connects it to the HAL, allowing the use of real I2C hardware in simulation. Note that these callbacks are called synchronously and in the same thread as the robot program; long delays in callbacks will block the main thread and can cause loop overruns. + +## Building the extension +To build an extension for use in a robot project, you'll need to build with Gradle. The easiest way to get a working build.gradle file is to copy the build.gradle file from halsim_xrp. It doesn't have any tests, and it only depends on halsim_ws_core. The important line is `lib project: ':wpinet', library: 'wpinet', linkage: 'shared'`. This tells Gradle to link the extension with wpinet using shared libraries. Other libraries can be included in a similar way by referencing the Gradle subproject name. Note that you do not need to include the HAL since it is automatically included. + +# Using a custom extension +After setting up a build.gradle file for a custom extension, follow the guides to build and publish your own local build of allwpilib. Once you've published a local build, follow the instructions in [DevelopmentBuilds.md](/DevelopmentBuilds.md) to use the locally published build in a robot project. Then, place this line your robot project's build.gradle file: +```groovy +wpi.sim.addDep("Custom Sim Extension", "edu.wpi.first.halsim", "pluginName") +``` +where `Custom Sim Extension` is the name of the extension shown by VS Code and `pluginName` is the same as `pluginName` declared in the build.gradle file for the simulation extension. + +# Built-in extensions +halsim_ds_socket: Allows the real Driver Station to control the robot program. + +halsim_gui: Provides the simulation GUI. + +halsim_ws_client: A websockets client that allows robot hardware interface state to be transmitted over websockets. + +halsim_ws_core: A websockets library for use by other extensions. Not directly usable. + +halsim_ws_server: A websockets server that allows robot hardware interface state to be transmitted over websockets. + +halsim_xrp: A client that supports the XRP protocol, allowing the robot program to control and receive data from the XRP. diff --git a/simulation/halsim_ds_socket/README.md b/simulation/halsim_ds_socket/README.md new file mode 100644 index 00000000000..c8f307838b1 --- /dev/null +++ b/simulation/halsim_ds_socket/README.md @@ -0,0 +1,6 @@ +# HAL DS Socket +This is an extension that allows the Driver Station to communicate with the robot program. Note that not everything has been reimplemented, since lots of DS data like battery voltage doesn't apply in simulation. + +# Configuration + +The only environment variable the extension supports is `DS_TIMEOUT_MS`, which is the amount of milliseconds it takes for a UDP packet to arrive from the DS before the robot program automatically disables. Default value is `100`, representing 100 milliseconds. From 7d64d4e24cb9b89ddc7cdb2484a762c461ab86e3 Mon Sep 17 00:00:00 2001 From: Wispy <101812473+WispySparks@users.noreply.github.com> Date: Mon, 15 Jul 2024 19:28:05 -0500 Subject: [PATCH 20/20] [sim] Add GUI support for the REV PH (#6704) --- .../cpp/hardware/{PCM.cpp => Pneumatic.cpp} | 51 ++-- .../glass/hardware/{PCM.h => Pneumatic.h} | 38 ++- .../src/main/native/cpp/PCMSimGui.cpp | 65 +++-- .../src/main/native/cpp/PCMSimGui.h | 6 + .../src/main/native/cpp/PHSimGui.cpp | 225 ++++++++++++++++++ .../halsim_gui/src/main/native/cpp/PHSimGui.h | 20 ++ .../halsim_gui/src/main/native/cpp/main.cpp | 36 +++ 7 files changed, 374 insertions(+), 67 deletions(-) rename glass/src/lib/native/cpp/hardware/{PCM.cpp => Pneumatic.cpp} (75%) rename glass/src/lib/native/include/glass/hardware/{PCM.h => Pneumatic.h} (50%) create mode 100644 simulation/halsim_gui/src/main/native/cpp/PHSimGui.cpp create mode 100644 simulation/halsim_gui/src/main/native/cpp/PHSimGui.h diff --git a/glass/src/lib/native/cpp/hardware/PCM.cpp b/glass/src/lib/native/cpp/hardware/Pneumatic.cpp similarity index 75% rename from glass/src/lib/native/cpp/hardware/PCM.cpp rename to glass/src/lib/native/cpp/hardware/Pneumatic.cpp index 6238fd9ae4d..10ec61e142b 100644 --- a/glass/src/lib/native/cpp/hardware/PCM.cpp +++ b/glass/src/lib/native/cpp/hardware/Pneumatic.cpp @@ -2,7 +2,7 @@ // 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 "glass/hardware/PCM.h" +#include "glass/hardware/Pneumatic.h" #include #include @@ -20,8 +20,8 @@ using namespace glass; -bool glass::DisplayPCMSolenoids(PCMModel* model, int index, - bool outputsEnabled) { +bool glass::DisplayPneumaticControlSolenoids(PneumaticControlModel* model, + int index, bool outputsEnabled) { wpi::SmallVector channels; model->ForEachSolenoid([&](SolenoidModel& solenoid, int j) { if (auto data = solenoid.GetOutputData()) { @@ -50,7 +50,8 @@ bool glass::DisplayPCMSolenoids(PCMModel* model, int index, wpi::format_to_n_c_str(label, sizeof(label), "{} [{}]###header", name, index); } else { - wpi::format_to_n_c_str(label, sizeof(label), "PCM[{}]###header", index); + wpi::format_to_n_c_str(label, sizeof(label), "{}[{}]###header", + model->GetName(), index); } // header @@ -85,32 +86,29 @@ bool glass::DisplayPCMSolenoids(PCMModel* model, int index, return true; } -void glass::DisplayPCMsSolenoids(PCMsModel* model, bool outputsEnabled, - std::string_view noneMsg) { +void glass::DisplayPneumaticControlsSolenoids(PneumaticControlsModel* model, + bool outputsEnabled, + std::string_view noneMsg) { bool hasAny = false; - model->ForEachPCM([&](PCMModel& pcm, int i) { - PushID(i); - if (DisplayPCMSolenoids(&pcm, i, outputsEnabled)) { - hasAny = true; - } - PopID(); - }); + model->ForEachPneumaticControl( + [&](PneumaticControlModel& pneumaticControl, int i) { + PushID(i); + if (DisplayPneumaticControlSolenoids(&pneumaticControl, i, + outputsEnabled)) { + hasAny = true; + } + PopID(); + }); if (!hasAny && !noneMsg.empty()) { ImGui::TextUnformatted(noneMsg.data(), noneMsg.data() + noneMsg.size()); } } -void glass::DisplayCompressorDevice(PCMModel* model, int index, +void glass::DisplayCompressorDevice(CompressorModel* model, int index, bool outputsEnabled) { - auto compressor = model->GetCompressor(); - if (!compressor || !compressor->Exists()) { + if (!model || !model->Exists()) { return; } - DisplayCompressorDevice(compressor, index, outputsEnabled); -} - -void glass::DisplayCompressorDevice(CompressorModel* model, int index, - bool outputsEnabled) { char name[32]; wpi::format_to_n_c_str(name, sizeof(name), "Compressor[{}]", index); @@ -155,8 +153,11 @@ void glass::DisplayCompressorDevice(CompressorModel* model, int index, } } -void glass::DisplayCompressorsDevice(PCMsModel* model, bool outputsEnabled) { - model->ForEachPCM([&](PCMModel& pcm, int i) { - DisplayCompressorDevice(&pcm, i, outputsEnabled); - }); +void glass::DisplayCompressorsDevice(PneumaticControlsModel* model, + bool outputsEnabled) { + model->ForEachPneumaticControl( + [&](PneumaticControlModel& pneumaticControl, int i) { + DisplayCompressorDevice(pneumaticControl.GetCompressor(), i, + outputsEnabled); + }); } diff --git a/glass/src/lib/native/include/glass/hardware/PCM.h b/glass/src/lib/native/include/glass/hardware/Pneumatic.h similarity index 50% rename from glass/src/lib/native/include/glass/hardware/PCM.h rename to glass/src/lib/native/include/glass/hardware/Pneumatic.h index 107a2a84fc6..0e9e525f261 100644 --- a/glass/src/lib/native/include/glass/hardware/PCM.h +++ b/glass/src/lib/native/include/glass/hardware/Pneumatic.h @@ -4,7 +4,9 @@ #pragma once +#include #include +#include #include @@ -34,27 +36,45 @@ class SolenoidModel : public Model { virtual void SetOutput(bool val) = 0; }; -class PCMModel : public Model { +class PneumaticControlModel : public Model { public: virtual CompressorModel* GetCompressor() = 0; virtual void ForEachSolenoid( wpi::function_ref func) = 0; + + virtual std::string_view GetName() = 0; }; -class PCMsModel : public Model { +class PneumaticControlsModel : public Model { public: - virtual void ForEachPCM( - wpi::function_ref func) = 0; + virtual void ForEachPneumaticControl( + wpi::function_ref + func) = 0; +}; + +struct AllPneumaticControlsModel : public Model { + AllPneumaticControlsModel(std::unique_ptr pcms, + std::unique_ptr phs) + : pcms{std::move(pcms)}, phs{std::move(phs)} {}; + std::unique_ptr pcms; + std::unique_ptr phs; + void Update() override { + pcms->Update(); + phs->Update(); + }; + bool Exists() override { return true; } }; -bool DisplayPCMSolenoids(PCMModel* model, int index, bool outputsEnabled); -void DisplayPCMsSolenoids(PCMsModel* model, bool outputsEnabled, - std::string_view noneMsg = "No solenoids"); +bool DisplayPneumaticControlSolenoids(PneumaticControlModel* model, int index, + bool outputsEnabled); +void DisplayPneumaticControlsSolenoids( + PneumaticControlsModel* model, bool outputsEnabled, + std::string_view noneMsg = "No solenoids"); -void DisplayCompressorDevice(PCMModel* model, int index, bool outputsEnabled); void DisplayCompressorDevice(CompressorModel* model, int index, bool outputsEnabled); -void DisplayCompressorsDevice(PCMsModel* model, bool outputsEnabled); +void DisplayCompressorsDevice(PneumaticControlsModel* model, + bool outputsEnabled); } // namespace glass diff --git a/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.cpp index 869c5b102cb..d5a3f3604e4 100644 --- a/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.cpp @@ -4,7 +4,7 @@ #include "PCMSimGui.h" -#include +#include #include #include @@ -25,7 +25,8 @@ namespace { HALSIMGUI_DATASOURCE_BOOLEAN_INDEXED(CTREPCMCompressorOn, "Compressor On"); HALSIMGUI_DATASOURCE_BOOLEAN_INDEXED(CTREPCMClosedLoopEnabled, "Closed Loop"); HALSIMGUI_DATASOURCE_BOOLEAN_INDEXED(CTREPCMPressureSwitch, "Pressure Switch"); -HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(CTREPCMCompressorCurrent, "Comp Current"); +HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(CTREPCMCompressorCurrent, + "Compressor Current"); HALSIMGUI_DATASOURCE_BOOLEAN_INDEXED2(CTREPCMSolenoidOutput, "Solenoid"); class CompressorSimModel : public glass::CompressorModel { @@ -90,7 +91,7 @@ class SolenoidSimModel : public glass::SolenoidModel { CTREPCMSolenoidOutputSource m_output; }; -class PCMSimModel : public glass::PCMModel { +class PCMSimModel : public glass::PneumaticControlModel { public: explicit PCMSimModel(int32_t index) : m_index{index}, @@ -107,6 +108,8 @@ class PCMSimModel : public glass::PCMModel { wpi::function_ref func) override; + std::string_view GetName() override { return "PCM"; } + int GetNumSolenoids() const { return m_solenoidInitCount; } private: @@ -116,7 +119,7 @@ class PCMSimModel : public glass::PCMModel { int m_solenoidInitCount = 0; }; -class PCMsSimModel : public glass::PCMsModel { +class PCMsSimModel : public glass::PneumaticControlsModel { public: PCMsSimModel() : m_models(HAL_GetNumCTREPCMModules()) {} @@ -124,8 +127,9 @@ class PCMsSimModel : public glass::PCMsModel { bool Exists() override { return true; } - void ForEachPCM( - wpi::function_ref func) override; + void ForEachPneumaticControl( + wpi::function_ref + func) override; private: std::vector> m_models; @@ -176,8 +180,9 @@ void PCMsSimModel::Update() { } } -void PCMsSimModel::ForEachPCM( - wpi::function_ref func) { +void PCMsSimModel::ForEachPneumaticControl( + wpi::function_ref + func) { int32_t numCTREPCMs = m_models.size(); for (int32_t i = 0; i < numCTREPCMs; ++i) { if (auto model = m_models[i].get()) { @@ -186,7 +191,7 @@ void PCMsSimModel::ForEachPCM( } } -static bool PCMsAnyInitialized() { +bool PCMSimGui::PCMsAnyInitialized() { static const int32_t num = HAL_GetNumCTREPCMModules(); for (int32_t i = 0; i < num; ++i) { if (HALSIM_GetCTREPCMInitialized(i)) { @@ -196,31 +201,25 @@ static bool PCMsAnyInitialized() { return false; } -void PCMSimGui::Initialize() { - HALSimGui::halProvider->RegisterModel("CTREPCMs", PCMsAnyInitialized, [] { - return std::make_unique(); - }); - HALSimGui::halProvider->RegisterView( - "Solenoids", "CTREPCMs", - [](glass::Model* model) { - bool any = false; - static_cast(model)->ForEachPCM( - [&](glass::PCMModel& CTREPCM, int) { - if (static_cast(&CTREPCM)->GetNumSolenoids() > 0) { - any = true; - } - }); - return any; - }, - [](glass::Window* win, glass::Model* model) { - win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); - win->SetDefaultPos(290, 20); - return glass::MakeFunctionView([=] { - glass::DisplayPCMsSolenoids( - static_cast(model), - HALSimGui::halProvider->AreOutputsEnabled()); - }); +bool PCMSimGui::PCMsAnySolenoids(glass::PneumaticControlsModel* model) { + bool any = false; + static_cast(model)->ForEachPneumaticControl( + [&](glass::PneumaticControlModel& CTREPCM, int) { + if (static_cast(&CTREPCM)->GetNumSolenoids() > 0) { + any = true; + } }); + return any; +} + +std::unique_ptr PCMSimGui::GetPCMsModel() { + return std::make_unique(); +} + +void PCMSimGui::Initialize() { + HALSimGui::halProvider->RegisterModel( + "CTREPCMs", PCMSimGui::PCMsAnyInitialized, + [] { return std::make_unique(); }); SimDeviceGui::GetDeviceTree().Add( HALSimGui::halProvider->GetModel("CTREPCMs"), [](glass::Model* model) { diff --git a/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.h b/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.h index aef771784d9..da20022ef14 100644 --- a/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.h +++ b/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.h @@ -3,12 +3,18 @@ // the WPILib BSD license file in the root directory of this project. #pragma once +#include + +#include namespace halsimgui { class PCMSimGui { public: static void Initialize(); + static bool PCMsAnyInitialized(); + static bool PCMsAnySolenoids(glass::PneumaticControlsModel* model); + static std::unique_ptr GetPCMsModel(); }; } // namespace halsimgui diff --git a/simulation/halsim_gui/src/main/native/cpp/PHSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/PHSimGui.cpp new file mode 100644 index 00000000000..47e65e1e5b2 --- /dev/null +++ b/simulation/halsim_gui/src/main/native/cpp/PHSimGui.cpp @@ -0,0 +1,225 @@ +// 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 "PHSimGui.h" + +#include +#include + +#include +#include +#include + +#include +#include +#include + +#include "HALDataSource.h" +#include "HALSimGui.h" +#include "SimDeviceGui.h" + +using namespace halsimgui; + +namespace { +HALSIMGUI_DATASOURCE_BOOLEAN_INDEXED(REVPHCompressorOn, "Compressor On"); +HALSIMGUI_DATASOURCE_BOOLEAN_INDEXED(REVPHPressureSwitch, "Pressure Switch"); +HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(REVPHCompressorCurrent, + "Compressor Current"); +HALSIMGUI_DATASOURCE_BOOLEAN_INDEXED2(REVPHSolenoidOutput, "Solenoid"); + +class CompressorSimModel : public glass::CompressorModel { + public: + explicit CompressorSimModel(int32_t index) + : m_index{index}, + m_running{index}, + m_pressureSwitch{index}, + m_current{index} {} + + void Update() override {} + + bool Exists() override { return HALSIM_GetREVPHInitialized(m_index); } + + glass::DataSource* GetRunningData() override { return &m_running; } + glass::DataSource* GetEnabledData() override { return nullptr; } + glass::DataSource* GetPressureSwitchData() override { + return &m_pressureSwitch; + } + glass::DataSource* GetCurrentData() override { return &m_current; } + + void SetRunning(bool val) override { + HALSIM_SetREVPHCompressorOn(m_index, val); + } + void SetEnabled(bool val) override {} + void SetPressureSwitch(bool val) override { + HALSIM_SetREVPHPressureSwitch(m_index, val); + } + void SetCurrent(double val) override { + HALSIM_SetREVPHCompressorCurrent(m_index, val); + } + + private: + int32_t m_index; + REVPHCompressorOnSource m_running; + REVPHPressureSwitchSource m_pressureSwitch; + REVPHCompressorCurrentSource m_current; +}; + +class SolenoidSimModel : public glass::SolenoidModel { + public: + SolenoidSimModel(int32_t index, int32_t channel) + : m_index{index}, m_channel{channel}, m_output{index, channel} {} + + void Update() override {} + + bool Exists() override { return HALSIM_GetREVPHInitialized(m_index); } + + glass::DataSource* GetOutputData() override { return &m_output; } + + void SetOutput(bool val) override { + HALSIM_SetREVPHSolenoidOutput(m_index, m_channel, val); + } + + private: + int32_t m_index; + int32_t m_channel; + REVPHSolenoidOutputSource m_output; +}; + +class PHSimModel : public glass::PneumaticControlModel { + public: + explicit PHSimModel(int32_t index) + : m_index{index}, + m_compressor{index}, + m_solenoids(HAL_GetNumREVPHChannels()) {} + + void Update() override; + + bool Exists() override { return true; } + + CompressorSimModel* GetCompressor() override { return &m_compressor; } + + void ForEachSolenoid( + wpi::function_ref func) + override; + + std::string_view GetName() override { return "PH"; } + + int GetNumSolenoids() const { return m_solenoidInitCount; } + + private: + int32_t m_index; + CompressorSimModel m_compressor; + std::vector> m_solenoids; + int m_solenoidInitCount = 0; +}; + +class PHsSimModel : public glass::PneumaticControlsModel { + public: + PHsSimModel() : m_models(HAL_GetNumREVPHModules()) {} + + void Update() override; + + bool Exists() override { return true; } + + void ForEachPneumaticControl( + wpi::function_ref + func) override; + + private: + std::vector> m_models; +}; +} // namespace + +void PHSimModel::Update() { + int32_t numChannels = m_solenoids.size(); + m_solenoidInitCount = 0; + for (int32_t i = 0; i < numChannels; ++i) { + auto& model = m_solenoids[i]; + if (HALSIM_GetREVPHInitialized(m_index)) { + if (!model) { + model = std::make_unique(m_index, i); + } + ++m_solenoidInitCount; + } else { + model.reset(); + } + } +} + +void PHSimModel::ForEachSolenoid( + wpi::function_ref func) { + if (m_solenoidInitCount == 0) { + return; + } + int32_t numSolenoids = m_solenoids.size(); + for (int32_t i = 0; i < numSolenoids; ++i) { + if (auto model = m_solenoids[i].get()) { + func(*model, i); + } + } +} + +void PHsSimModel::Update() { + for (int32_t i = 0, iend = static_cast(m_models.size()); i < iend; + ++i) { + auto& model = m_models[i]; + if (HALSIM_GetREVPHInitialized(i)) { + if (!model) { + model = std::make_unique(i); + } + model->Update(); + } else { + model.reset(); + } + } +} + +void PHsSimModel::ForEachPneumaticControl( + wpi::function_ref + func) { + int32_t numREVPHs = m_models.size(); + for (int32_t i = 0; i < numREVPHs; ++i) { + if (auto model = m_models[i].get()) { + func(*model, i); + } + } +} + +bool PHSimGui::PHsAnyInitialized() { + static const int32_t num = HAL_GetNumREVPHModules(); + for (int32_t i = 0; i < num; ++i) { + if (HALSIM_GetREVPHInitialized(i)) { + return true; + } + } + return false; +} + +bool PHSimGui::PHsAnySolenoids(glass::PneumaticControlsModel* model) { + bool any = false; + static_cast(model)->ForEachPneumaticControl( + [&](glass::PneumaticControlModel& REVPH, int) { + if (static_cast(&REVPH)->GetNumSolenoids() > 0) { + any = true; + } + }); + return any; +} + +std::unique_ptr PHSimGui::GetPHsModel() { + return std::make_unique(); +} + +void PHSimGui::Initialize() { + HALSimGui::halProvider->RegisterModel( + "REVPHs", PHSimGui::PHsAnyInitialized, + [] { return std::make_unique(); }); + + SimDeviceGui::GetDeviceTree().Add( + HALSimGui::halProvider->GetModel("REVPHs"), [](glass::Model* model) { + glass::DisplayCompressorsDevice( + static_cast(model), + HALSimGui::halProvider->AreOutputsEnabled()); + }); +} diff --git a/simulation/halsim_gui/src/main/native/cpp/PHSimGui.h b/simulation/halsim_gui/src/main/native/cpp/PHSimGui.h new file mode 100644 index 00000000000..84fe9d76ac7 --- /dev/null +++ b/simulation/halsim_gui/src/main/native/cpp/PHSimGui.h @@ -0,0 +1,20 @@ +// 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 + +namespace halsimgui { + +class PHSimGui { + public: + static void Initialize(); + static bool PHsAnyInitialized(); + static bool PHsAnySolenoids(glass::PneumaticControlsModel* model); + static std::unique_ptr GetPHsModel(); +}; + +} // namespace halsimgui diff --git a/simulation/halsim_gui/src/main/native/cpp/main.cpp b/simulation/halsim_gui/src/main/native/cpp/main.cpp index 54510239bc8..574090b974c 100644 --- a/simulation/halsim_gui/src/main/native/cpp/main.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/main.cpp @@ -4,6 +4,7 @@ #include #include +#include #include #include @@ -26,6 +27,7 @@ #include "HALSimGuiExt.h" #include "NetworkTablesSimGui.h" #include "PCMSimGui.h" +#include "PHSimGui.h" #include "PWMSimGui.h" #include "PowerDistributionSimGui.h" #include "RelaySimGui.h" @@ -85,9 +87,43 @@ __declspec(dllexport) PowerDistributionSimGui::Initialize(); PWMSimGui::Initialize(); RelaySimGui::Initialize(); + PHSimGui::Initialize(); RoboRioSimGui::Initialize(); TimingGui::Initialize(); + HALSimGui::halProvider->RegisterModel( + "AllPneumaticControls", + [] { + return PCMSimGui::PCMsAnyInitialized() || PHSimGui::PHsAnyInitialized(); + }, + [] { + return std::make_unique( + PCMSimGui::GetPCMsModel(), PHSimGui::GetPHsModel()); + }); + + HALSimGui::halProvider->RegisterView( + "Solenoids", "AllPneumaticControls", + [](glass::Model* model) { + auto pneumaticModel = + static_cast(model); + return PCMSimGui::PCMsAnySolenoids(pneumaticModel->pcms.get()) || + PHSimGui::PHsAnySolenoids(pneumaticModel->phs.get()); + }, + [](glass::Window* win, glass::Model* model) { + win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); + win->SetDefaultPos(290, 20); + return glass::MakeFunctionView([=] { + auto pneumaticModel = + static_cast(model); + glass::DisplayPneumaticControlsSolenoids( + pneumaticModel->pcms.get(), + HALSimGui::halProvider->AreOutputsEnabled()); + glass::DisplayPneumaticControlsSolenoids( + pneumaticModel->phs.get(), + HALSimGui::halProvider->AreOutputsEnabled()); + }); + }); + HALSimGui::mainMenu.AddMainMenu([] { if (ImGui::BeginMenu("Hardware")) { HALSimGui::halProvider->DisplayMenu();