From 382deef75055ea19428f03219e148d62b25ef0ca Mon Sep 17 00:00:00 2001 From: Thad House Date: Fri, 20 Aug 2021 09:02:01 -0700 Subject: [PATCH] [wpimath] Explicitly export wpimath symbols Co-authored-by: Tyler Veness --- cmake/modules/AddTest.cmake | 2 +- cmake/modules/CompileWarnings.cmake | 2 +- shared/jni/setupBuild.gradle | 2 ++ wpimath/CMakeLists.txt | 3 ++ wpimath/build.gradle | 31 ------------------- .../constraint/MaxVelocityConstraint.cpp | 23 ++++++++++++++ .../discrete_algebraic_riccati_equation.h | 3 ++ .../src/main/native/include/frc/MathUtil.h | 3 ++ .../main/native/include/frc/StateSpaceUtil.h | 13 +++++--- .../include/frc/controller/ArmFeedforward.h | 3 +- .../frc/controller/HolonomicDriveController.h | 4 ++- .../frc/controller/LinearQuadraticRegulator.h | 7 +++-- .../include/frc/controller/PIDController.h | 6 ++-- .../frc/controller/ProfiledPIDController.h | 2 ++ .../frc/controller/RamseteController.h | 4 ++- .../DifferentialDrivePoseEstimator.h | 3 +- .../include/frc/estimator/KalmanFilter.h | 7 +++-- .../frc/estimator/MecanumDrivePoseEstimator.h | 3 +- .../main/native/include/frc/geometry/Pose2d.h | 6 +++- .../native/include/frc/geometry/Rotation2d.h | 6 +++- .../native/include/frc/geometry/Transform2d.h | 6 ++-- .../include/frc/geometry/Translation2d.h | 6 +++- .../native/include/frc/geometry/Twist2d.h | 4 ++- .../include/frc/kinematics/ChassisSpeeds.h | 4 ++- .../kinematics/DifferentialDriveKinematics.h | 4 ++- .../kinematics/DifferentialDriveOdometry.h | 4 ++- .../kinematics/DifferentialDriveWheelSpeeds.h | 4 ++- .../frc/kinematics/MecanumDriveKinematics.h | 4 ++- .../frc/kinematics/MecanumDriveOdometry.h | 3 +- .../frc/kinematics/MecanumDriveWheelSpeeds.h | 4 ++- .../frc/kinematics/SwerveModuleState.h | 4 ++- .../include/frc/spline/CubicHermiteSpline.h | 3 +- .../include/frc/spline/QuinticHermiteSpline.h | 3 +- .../native/include/frc/spline/SplineHelper.h | 3 +- .../include/frc/spline/SplineParameterizer.h | 4 ++- .../native/include/frc/system/plant/DCMotor.h | 4 ++- .../include/frc/system/plant/LinearSystemId.h | 5 +-- .../include/frc/trajectory/Trajectory.h | 8 +++-- .../include/frc/trajectory/TrajectoryConfig.h | 4 ++- .../frc/trajectory/TrajectoryGenerator.h | 4 ++- .../frc/trajectory/TrajectoryParameterizer.h | 4 ++- .../include/frc/trajectory/TrajectoryUtil.h | 4 ++- .../CentripetalAccelerationConstraint.h | 5 ++- .../DifferentialDriveKinematicsConstraint.h | 5 ++- .../DifferentialDriveVoltageConstraint.h | 5 ++- .../constraint/MaxVelocityConstraint.h | 15 ++++----- .../MecanumDriveKinematicsConstraint.h | 5 ++- .../SwerveDriveKinematicsConstraint.h | 3 +- .../SwerveDriveKinematicsConstraint.inc | 6 ---- .../constraint/TrajectoryConstraint.h | 4 ++- wpimath/src/main/native/include/units/base.h | 2 ++ .../main/native/include/wpimath/MathShared.h | 5 +-- .../main/native/include/wpi/SymbolExports.h | 23 ++++++++++++++ .../native/include/wpi/sendable/Sendable.h | 4 ++- 54 files changed, 207 insertions(+), 101 deletions(-) create mode 100644 wpimath/src/main/native/cpp/trajectory/constraint/MaxVelocityConstraint.cpp create mode 100644 wpiutil/src/main/native/include/wpi/SymbolExports.h diff --git a/cmake/modules/AddTest.cmake b/cmake/modules/AddTest.cmake index c8ef579faa..eef41131e2 100644 --- a/cmake/modules/AddTest.cmake +++ b/cmake/modules/AddTest.cmake @@ -8,7 +8,7 @@ macro(wpilib_add_test name srcdir) target_compile_definitions(${name}_test PRIVATE -DGTEST_LINKED_AS_SHARED_LIBRARY) endif() if (MSVC) - target_compile_options(${name}_test PRIVATE /wd4251 /wd4101) + target_compile_options(${name}_test PRIVATE /wd4101 /wd4251) endif() add_test(NAME ${name} COMMAND ${name}_test) endmacro() diff --git a/cmake/modules/CompileWarnings.cmake b/cmake/modules/CompileWarnings.cmake index 0eb9733c1a..f35f975cdf 100644 --- a/cmake/modules/CompileWarnings.cmake +++ b/cmake/modules/CompileWarnings.cmake @@ -2,6 +2,6 @@ macro(wpilib_target_warnings target) if(NOT MSVC) target_compile_options(${target} PRIVATE -Wall -pedantic -Wextra -Werror -Wno-unused-parameter -Wno-error=deprecated-declarations) else() - target_compile_options(${target} PRIVATE /wd4244 /wd4267 /wd4146 /WX /wd4996) + target_compile_options(${target} PRIVATE /wd4146 /wd4244 /wd4251 /wd4267 /wd4996 /WX) endif() endmacro() diff --git a/shared/jni/setupBuild.gradle b/shared/jni/setupBuild.gradle index 76359eb10a..a68ad598de 100644 --- a/shared/jni/setupBuild.gradle +++ b/shared/jni/setupBuild.gradle @@ -59,6 +59,8 @@ model { it.buildable = false return } + it.cppCompiler.define 'WPILIB_EXPORTS' + it.cCompiler.define 'WPILIB_EXPORTS' if (!project.hasProperty('noWpiutil')) { lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared' } diff --git a/wpimath/CMakeLists.txt b/wpimath/CMakeLists.txt index a141201662..2a4090f3fc 100644 --- a/wpimath/CMakeLists.txt +++ b/wpimath/CMakeLists.txt @@ -92,10 +92,13 @@ endif() file(GLOB_RECURSE wpimath_native_src src/main/native/cpp/*.cpp) list(REMOVE_ITEM wpimath_native_src ${wpimath_jni_src}) +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS FALSE) add_library(wpimath ${wpimath_native_src}) +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS TRUE) set_target_properties(wpimath PROPERTIES DEBUG_POSTFIX "d") set_property(TARGET wpimath PROPERTY FOLDER "libraries") +target_compile_definitions(wpimath PRIVATE WPILIB_EXPORTS) target_compile_features(wpimath PUBLIC cxx_std_17) if (MSVC) diff --git a/wpimath/build.gradle b/wpimath/build.gradle index 6815cbd668..79db4bc4d2 100644 --- a/wpimath/build.gradle +++ b/wpimath/build.gradle @@ -13,37 +13,6 @@ ext { apply from: "${rootDir}/shared/jni/setupBuild.gradle" -nativeUtils.exportsConfigs { - wpimath { - x86ExcludeSymbols = [ - '_CT??_R0?AV_System_error', - '_CT??_R0?AVexception', - '_CT??_R0?AVfailure', - '_CT??_R0?AVruntime_error', - '_CT??_R0?AVsystem_error', - '_CTA5?AVfailure', - '_TI5?AVfailure', - '_CT??_R0?AVout_of_range', - '_CTA3?AVout_of_range', - '_TI3?AVout_of_range', - '_CT??_R0?AVbad_cast' - ] - x64ExcludeSymbols = [ - '_CT??_R0?AV_System_error', - '_CT??_R0?AVexception', - '_CT??_R0?AVfailure', - '_CT??_R0?AVruntime_error', - '_CT??_R0?AVsystem_error', - '_CTA5?AVfailure', - '_TI5?AVfailure', - '_CT??_R0?AVout_of_range', - '_CTA3?AVout_of_range', - '_TI3?AVout_of_range', - '_CT??_R0?AVbad_cast' - ] - } -} - cppHeadersZip { from('src/main/native/eigeninclude') { into '/' diff --git a/wpimath/src/main/native/cpp/trajectory/constraint/MaxVelocityConstraint.cpp b/wpimath/src/main/native/cpp/trajectory/constraint/MaxVelocityConstraint.cpp new file mode 100644 index 0000000000..9e6e712923 --- /dev/null +++ b/wpimath/src/main/native/cpp/trajectory/constraint/MaxVelocityConstraint.cpp @@ -0,0 +1,23 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "frc/trajectory/constraint/MaxVelocityConstraint.h" + +using namespace frc; + +MaxVelocityConstraint::MaxVelocityConstraint( + units::meters_per_second_t maxVelocity) + : m_maxVelocity(units::math::abs(maxVelocity)) {} + +units::meters_per_second_t MaxVelocityConstraint::MaxVelocity( + const Pose2d& pose, units::curvature_t curvature, + units::meters_per_second_t velocity) const { + return m_maxVelocity; +} + +TrajectoryConstraint::MinMax MaxVelocityConstraint::MinMaxAcceleration( + const Pose2d& pose, units::curvature_t curvature, + units::meters_per_second_t speed) const { + return {}; +} diff --git a/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h b/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h index cb0a4ee131..5d7a316f3d 100644 --- a/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h +++ b/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h @@ -4,6 +4,7 @@ #include #include +#include namespace drake { namespace math { @@ -20,6 +21,7 @@ namespace math { /// "On the Numerical Solution of the Discrete-Time Algebraic Riccati Equation" /// by Thrasyvoulos Pappas, Alan J. Laub, and Nils R. Sandell /// +WPILIB_DLLEXPORT Eigen::MatrixXd DiscreteAlgebraicRiccatiEquation( const Eigen::Ref& A, const Eigen::Ref& B, @@ -69,6 +71,7 @@ Eigen::MatrixXd DiscreteAlgebraicRiccatiEquation( /// @throws std::runtime_error if Q − NR⁻¹Nᵀ is not positive semi-definite. /// @throws std::runtime_error if R is not positive definite. /// +WPILIB_DLLEXPORT Eigen::MatrixXd DiscreteAlgebraicRiccatiEquation( const Eigen::Ref& A, const Eigen::Ref& B, diff --git a/wpimath/src/main/native/include/frc/MathUtil.h b/wpimath/src/main/native/include/frc/MathUtil.h index 3ea753da2a..54a77afb99 100644 --- a/wpimath/src/main/native/include/frc/MathUtil.h +++ b/wpimath/src/main/native/include/frc/MathUtil.h @@ -4,6 +4,7 @@ #pragma once +#include #include #include "units/angle.h" @@ -17,6 +18,7 @@ namespace frc { * @param value Value to clip. * @param deadband Range around zero. */ +WPILIB_DLLEXPORT double ApplyDeadband(double value, double deadband); /** @@ -46,6 +48,7 @@ constexpr T InputModulus(T input, T minimumInput, T maximumInput) { * * @param angle Angle to wrap. */ +WPILIB_DLLEXPORT constexpr units::radian_t AngleModulus(units::radian_t angle) { return InputModulus(angle, units::radian_t{-wpi::numbers::pi}, diff --git a/wpimath/src/main/native/include/frc/StateSpaceUtil.h b/wpimath/src/main/native/include/frc/StateSpaceUtil.h index 371003fc21..064fac381c 100644 --- a/wpimath/src/main/native/include/frc/StateSpaceUtil.h +++ b/wpimath/src/main/native/include/frc/StateSpaceUtil.h @@ -9,6 +9,8 @@ #include #include +#include + #include "Eigen/Core" #include "Eigen/Eigenvalues" #include "Eigen/QR" @@ -236,6 +238,7 @@ Eigen::Matrix MakeWhiteNoiseVector( * * @return The vector. */ +WPILIB_DLLEXPORT Eigen::Matrix PoseTo3dVector(const Pose2d& pose); /** @@ -245,6 +248,7 @@ Eigen::Matrix PoseTo3dVector(const Pose2d& pose); * * @return The vector. */ +WPILIB_DLLEXPORT Eigen::Matrix PoseTo4dVector(const Pose2d& pose); /** @@ -266,14 +270,14 @@ bool IsStabilizable(const Eigen::Matrix& A, // Template specializations are used here to make common state-input pairs // compile faster. template <> -bool IsStabilizable<1, 1>(const Eigen::Matrix& A, - const Eigen::Matrix& B); +WPILIB_DLLEXPORT bool IsStabilizable<1, 1>( + const Eigen::Matrix& A, const Eigen::Matrix& B); // Template specializations are used here to make common state-input pairs // compile faster. template <> -bool IsStabilizable<2, 1>(const Eigen::Matrix& A, - const Eigen::Matrix& B); +WPILIB_DLLEXPORT bool IsStabilizable<2, 1>( + const Eigen::Matrix& A, const Eigen::Matrix& B); /** * Converts a Pose2d into a vector of [x, y, theta]. @@ -282,6 +286,7 @@ bool IsStabilizable<2, 1>(const Eigen::Matrix& A, * * @return The vector. */ +WPILIB_DLLEXPORT Eigen::Matrix PoseToVector(const Pose2d& pose); /** diff --git a/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h b/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h index f3bdbd9d59..eb7cb76bbd 100644 --- a/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h +++ b/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h @@ -5,6 +5,7 @@ #pragma once #include +#include #include "units/angle.h" #include "units/angular_velocity.h" @@ -16,7 +17,7 @@ namespace frc { * A helper class that computes feedforward outputs for a simple arm (modeled as * a motor acting against the force of gravity on a beam suspended at an angle). */ -class ArmFeedforward { +class WPILIB_DLLEXPORT ArmFeedforward { public: using Angle = units::radians; using Velocity = units::radians_per_second; diff --git a/wpimath/src/main/native/include/frc/controller/HolonomicDriveController.h b/wpimath/src/main/native/include/frc/controller/HolonomicDriveController.h index 483e5d1430..265ff31019 100644 --- a/wpimath/src/main/native/include/frc/controller/HolonomicDriveController.h +++ b/wpimath/src/main/native/include/frc/controller/HolonomicDriveController.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "frc/controller/PIDController.h" #include "frc/controller/ProfiledPIDController.h" #include "frc/geometry/Pose2d.h" @@ -27,7 +29,7 @@ namespace frc { * translations, users can specify a custom heading that the drivetrain should * point toward. This heading reference is profiled for smoothness. */ -class HolonomicDriveController { +class WPILIB_DLLEXPORT HolonomicDriveController { public: /** * Constructs a holonomic drive controller. diff --git a/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h b/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h index 439d6ae398..424af044d7 100644 --- a/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h +++ b/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h @@ -4,6 +4,7 @@ #pragma once +#include #include #include "Eigen/Cholesky" @@ -321,7 +322,7 @@ class LinearQuadraticRegulator // Template specializations are used here to make common state-input pairs // compile faster. template <> -class LinearQuadraticRegulator<1, 1> +class WPILIB_DLLEXPORT LinearQuadraticRegulator<1, 1> : public detail::LinearQuadraticRegulatorImpl<1, 1> { public: template @@ -357,7 +358,7 @@ class LinearQuadraticRegulator<1, 1> // Template specializations are used here to make common state-input pairs // compile faster. template <> -class LinearQuadraticRegulator<2, 1> +class WPILIB_DLLEXPORT LinearQuadraticRegulator<2, 1> : public detail::LinearQuadraticRegulatorImpl<2, 1> { public: template @@ -393,7 +394,7 @@ class LinearQuadraticRegulator<2, 1> // Template specializations are used here to make common state-input pairs // compile faster. template <> -class LinearQuadraticRegulator<2, 2> +class WPILIB_DLLEXPORT LinearQuadraticRegulator<2, 2> : public detail::LinearQuadraticRegulatorImpl<2, 2> { public: template diff --git a/wpimath/src/main/native/include/frc/controller/PIDController.h b/wpimath/src/main/native/include/frc/controller/PIDController.h index 9c1703edf0..2dfb9e520a 100644 --- a/wpimath/src/main/native/include/frc/controller/PIDController.h +++ b/wpimath/src/main/native/include/frc/controller/PIDController.h @@ -7,6 +7,7 @@ #include #include +#include #include #include @@ -17,8 +18,9 @@ namespace frc2 { /** * Implements a PID control loop. */ -class PIDController : public wpi::Sendable, - public wpi::SendableHelper { +class WPILIB_DLLEXPORT PIDController + : public wpi::Sendable, + public wpi::SendableHelper { public: /** * Allocates a PIDController with the given constants for Kp, Ki, and Kd. diff --git a/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h b/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h index 60f5b85e72..9fc75e7f23 100644 --- a/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h +++ b/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h @@ -9,6 +9,7 @@ #include #include +#include #include #include #include @@ -20,6 +21,7 @@ namespace frc { namespace detail { +WPILIB_DLLEXPORT void ReportProfiledPIDController(); } // namespace detail diff --git a/wpimath/src/main/native/include/frc/controller/RamseteController.h b/wpimath/src/main/native/include/frc/controller/RamseteController.h index c548ef6882..022fff9fe7 100644 --- a/wpimath/src/main/native/include/frc/controller/RamseteController.h +++ b/wpimath/src/main/native/include/frc/controller/RamseteController.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "frc/geometry/Pose2d.h" #include "frc/kinematics/ChassisSpeeds.h" #include "frc/trajectory/Trajectory.h" @@ -39,7 +41,7 @@ namespace frc { * See section * on Ramsete unicycle controller for a derivation and analysis. */ -class RamseteController { +class WPILIB_DLLEXPORT RamseteController { public: /** * Construct a Ramsete unicycle controller. diff --git a/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h b/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h index 95f2217f28..e59b162e64 100644 --- a/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h +++ b/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h @@ -4,6 +4,7 @@ #pragma once +#include #include #include "Eigen/Core" @@ -44,7 +45,7 @@ namespace frc { * y = [[x, y, theta]]ᵀ from vision, * or y = [[dist_l, dist_r, theta]] from encoders and gyro. */ -class DifferentialDrivePoseEstimator { +class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator { public: /** * Constructs a DifferentialDrivePoseEstimator. diff --git a/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h b/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h index 1ee7aae8dc..341e43d9bf 100644 --- a/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h +++ b/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h @@ -6,6 +6,7 @@ #include +#include #include #include "Eigen/Cholesky" @@ -209,7 +210,8 @@ class KalmanFilter : public detail::KalmanFilterImpl { // Template specializations are used here to make common state-input-output // triplets compile faster. template <> -class KalmanFilter<1, 1, 1> : public detail::KalmanFilterImpl<1, 1, 1> { +class WPILIB_DLLEXPORT KalmanFilter<1, 1, 1> + : public detail::KalmanFilterImpl<1, 1, 1> { public: KalmanFilter(LinearSystem<1, 1, 1>& plant, const wpi::array& stateStdDevs, @@ -223,7 +225,8 @@ class KalmanFilter<1, 1, 1> : public detail::KalmanFilterImpl<1, 1, 1> { // Template specializations are used here to make common state-input-output // triplets compile faster. template <> -class KalmanFilter<2, 1, 1> : public detail::KalmanFilterImpl<2, 1, 1> { +class WPILIB_DLLEXPORT KalmanFilter<2, 1, 1> + : public detail::KalmanFilterImpl<2, 1, 1> { public: KalmanFilter(LinearSystem<2, 1, 1>& plant, const wpi::array& stateStdDevs, diff --git a/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h b/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h index 61f748c0cf..fc58a6acfb 100644 --- a/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h +++ b/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h @@ -6,6 +6,7 @@ #include +#include #include #include "Eigen/Core" @@ -42,7 +43,7 @@ namespace frc { * coords from vision, or y = [[theta]]ᵀ * from the gyro. */ -class MecanumDrivePoseEstimator { +class WPILIB_DLLEXPORT MecanumDrivePoseEstimator { public: /** * Constructs a MecanumDrivePoseEstimator. diff --git a/wpimath/src/main/native/include/frc/geometry/Pose2d.h b/wpimath/src/main/native/include/frc/geometry/Pose2d.h index 310fd8116e..ebaa7c193e 100644 --- a/wpimath/src/main/native/include/frc/geometry/Pose2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Pose2d.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "Transform2d.h" #include "Translation2d.h" #include "Twist2d.h" @@ -17,7 +19,7 @@ namespace frc { /** * Represents a 2d pose containing translational and rotational elements. */ -class Pose2d { +class WPILIB_DLLEXPORT Pose2d { public: /** * Constructs a pose at the origin facing toward the positive X axis. @@ -171,8 +173,10 @@ class Pose2d { Rotation2d m_rotation; }; +WPILIB_DLLEXPORT void to_json(wpi::json& json, const Pose2d& pose); +WPILIB_DLLEXPORT void from_json(const wpi::json& json, Pose2d& pose); } // namespace frc diff --git a/wpimath/src/main/native/include/frc/geometry/Rotation2d.h b/wpimath/src/main/native/include/frc/geometry/Rotation2d.h index 9f6d1b02a1..94a17fc0ca 100644 --- a/wpimath/src/main/native/include/frc/geometry/Rotation2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Rotation2d.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "units/angle.h" namespace wpi { @@ -16,7 +18,7 @@ namespace frc { * A rotation in a 2d coordinate frame represented a point on the unit circle * (cosine and sine). */ -class Rotation2d { +class WPILIB_DLLEXPORT Rotation2d { public: /** * Constructs a Rotation2d with a default angle of 0 degrees. @@ -160,8 +162,10 @@ class Rotation2d { double m_sin = 0; }; +WPILIB_DLLEXPORT void to_json(wpi::json& json, const Rotation2d& rotation); +WPILIB_DLLEXPORT void from_json(const wpi::json& json, Rotation2d& rotation); } // namespace frc diff --git a/wpimath/src/main/native/include/frc/geometry/Transform2d.h b/wpimath/src/main/native/include/frc/geometry/Transform2d.h index 87c3b93ccf..3d5e1d6d4e 100644 --- a/wpimath/src/main/native/include/frc/geometry/Transform2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Transform2d.h @@ -4,16 +4,18 @@ #pragma once +#include + #include "Translation2d.h" namespace frc { -class Pose2d; +class WPILIB_DLLEXPORT Pose2d; /** * Represents a transformation for a Pose2d. */ -class Transform2d { +class WPILIB_DLLEXPORT Transform2d { public: /** * Constructs the transform that maps the initial pose to the final pose. diff --git a/wpimath/src/main/native/include/frc/geometry/Translation2d.h b/wpimath/src/main/native/include/frc/geometry/Translation2d.h index f49cd6385a..204da30b40 100644 --- a/wpimath/src/main/native/include/frc/geometry/Translation2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Translation2d.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "Rotation2d.h" #include "units/length.h" @@ -21,7 +23,7 @@ namespace frc { * When the robot is placed on the origin, facing toward the X direction, * moving forward increases the X, whereas moving to the left increases the Y. */ -class Translation2d { +class WPILIB_DLLEXPORT Translation2d { public: /** * Constructs a Translation2d with X and Y components equal to zero. @@ -175,8 +177,10 @@ class Translation2d { units::meter_t m_y = 0_m; }; +WPILIB_DLLEXPORT void to_json(wpi::json& json, const Translation2d& state); +WPILIB_DLLEXPORT void from_json(const wpi::json& json, Translation2d& state); } // namespace frc diff --git a/wpimath/src/main/native/include/frc/geometry/Twist2d.h b/wpimath/src/main/native/include/frc/geometry/Twist2d.h index 9aeeda49f8..9d7a856b56 100644 --- a/wpimath/src/main/native/include/frc/geometry/Twist2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Twist2d.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "units/angle.h" #include "units/length.h" #include "units/math.h" @@ -16,7 +18,7 @@ namespace frc { * * A Twist can be used to represent a difference between two poses. */ -struct Twist2d { +struct WPILIB_DLLEXPORT Twist2d { /** * Linear "dx" component */ diff --git a/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h b/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h index 61027e1cf0..7414deca21 100644 --- a/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h +++ b/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "frc/geometry/Rotation2d.h" #include "units/angular_velocity.h" #include "units/velocity.h" @@ -20,7 +22,7 @@ namespace frc { * never have a dy component because it can never move sideways. Holonomic * drivetrains such as swerve and mecanum will often have all three components. */ -struct ChassisSpeeds { +struct WPILIB_DLLEXPORT ChassisSpeeds { /** * Represents forward velocity w.r.t the robot frame of reference. (Fwd is +) */ diff --git a/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h b/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h index 85edb24beb..4bf27ff6ac 100644 --- a/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "frc/kinematics/ChassisSpeeds.h" #include "frc/kinematics/DifferentialDriveWheelSpeeds.h" #include "units/angle.h" @@ -19,7 +21,7 @@ namespace frc { * velocity components whereas forward kinematics converts left and right * component velocities into a linear and angular chassis speed. */ -class DifferentialDriveKinematics { +class WPILIB_DLLEXPORT DifferentialDriveKinematics { public: /** * Constructs a differential drive kinematics object. diff --git a/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h b/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h index 70a70e7d7d..70179def1d 100644 --- a/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h +++ b/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "DifferentialDriveKinematics.h" #include "frc/geometry/Pose2d.h" #include "units/length.h" @@ -21,7 +23,7 @@ namespace frc { * It is important that you reset your encoders to zero before using this class. * Any subsequent pose resets also require the encoders to be reset to zero. */ -class DifferentialDriveOdometry { +class WPILIB_DLLEXPORT DifferentialDriveOdometry { public: /** * Constructs a DifferentialDriveOdometry object. diff --git a/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveWheelSpeeds.h b/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveWheelSpeeds.h index 21efd87b1d..2bf9fb9738 100644 --- a/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveWheelSpeeds.h +++ b/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveWheelSpeeds.h @@ -4,13 +4,15 @@ #pragma once +#include + #include "units/velocity.h" namespace frc { /** * Represents the wheel speeds for a differential drive drivetrain. */ -struct DifferentialDriveWheelSpeeds { +struct WPILIB_DLLEXPORT DifferentialDriveWheelSpeeds { /** * Speed of the left side of the robot. */ diff --git a/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h b/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h index 7971c01735..9a7cef9e56 100644 --- a/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "Eigen/Core" #include "Eigen/QR" #include "frc/geometry/Translation2d.h" @@ -35,7 +37,7 @@ namespace frc { * Forward kinematics is also used for odometry -- determining the position of * the robot on the field using encoders and a gyro. */ -class MecanumDriveKinematics { +class WPILIB_DLLEXPORT MecanumDriveKinematics { public: /** * Constructs a mecanum drive kinematics object. diff --git a/wpimath/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h b/wpimath/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h index 62e9cb6d67..bdd12397cd 100644 --- a/wpimath/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h +++ b/wpimath/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h @@ -4,6 +4,7 @@ #pragma once +#include #include #include "frc/geometry/Pose2d.h" @@ -22,7 +23,7 @@ namespace frc { * path following. Furthermore, odometry can be used for latency compensation * when using computer-vision systems. */ -class MecanumDriveOdometry { +class WPILIB_DLLEXPORT MecanumDriveOdometry { public: /** * Constructs a MecanumDriveOdometry object. diff --git a/wpimath/src/main/native/include/frc/kinematics/MecanumDriveWheelSpeeds.h b/wpimath/src/main/native/include/frc/kinematics/MecanumDriveWheelSpeeds.h index b71eb7a626..c24b134542 100644 --- a/wpimath/src/main/native/include/frc/kinematics/MecanumDriveWheelSpeeds.h +++ b/wpimath/src/main/native/include/frc/kinematics/MecanumDriveWheelSpeeds.h @@ -4,13 +4,15 @@ #pragma once +#include + #include "units/velocity.h" namespace frc { /** * Represents the wheel speeds for a mecanum drive drivetrain. */ -struct MecanumDriveWheelSpeeds { +struct WPILIB_DLLEXPORT MecanumDriveWheelSpeeds { /** * Speed of the front-left wheel. */ diff --git a/wpimath/src/main/native/include/frc/kinematics/SwerveModuleState.h b/wpimath/src/main/native/include/frc/kinematics/SwerveModuleState.h index 52dfe8eff0..cae2d53b2b 100644 --- a/wpimath/src/main/native/include/frc/kinematics/SwerveModuleState.h +++ b/wpimath/src/main/native/include/frc/kinematics/SwerveModuleState.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "frc/geometry/Rotation2d.h" #include "units/angle.h" #include "units/math.h" @@ -13,7 +15,7 @@ namespace frc { /** * Represents the state of one swerve module. */ -struct SwerveModuleState { +struct WPILIB_DLLEXPORT SwerveModuleState { /** * Speed of the wheel of the module. */ diff --git a/wpimath/src/main/native/include/frc/spline/CubicHermiteSpline.h b/wpimath/src/main/native/include/frc/spline/CubicHermiteSpline.h index b908bb2e50..cfad20c3d5 100644 --- a/wpimath/src/main/native/include/frc/spline/CubicHermiteSpline.h +++ b/wpimath/src/main/native/include/frc/spline/CubicHermiteSpline.h @@ -4,6 +4,7 @@ #pragma once +#include #include #include "Eigen/Core" @@ -13,7 +14,7 @@ namespace frc { /** * Represents a hermite spline of degree 3. */ -class CubicHermiteSpline : public Spline<3> { +class WPILIB_DLLEXPORT CubicHermiteSpline : public Spline<3> { public: /** * Constructs a cubic hermite spline with the specified control vectors. Each diff --git a/wpimath/src/main/native/include/frc/spline/QuinticHermiteSpline.h b/wpimath/src/main/native/include/frc/spline/QuinticHermiteSpline.h index 05df2fe432..04efecde3a 100644 --- a/wpimath/src/main/native/include/frc/spline/QuinticHermiteSpline.h +++ b/wpimath/src/main/native/include/frc/spline/QuinticHermiteSpline.h @@ -4,6 +4,7 @@ #pragma once +#include #include #include "Eigen/Core" @@ -13,7 +14,7 @@ namespace frc { /** * Represents a hermite spline of degree 5. */ -class QuinticHermiteSpline : public Spline<5> { +class WPILIB_DLLEXPORT QuinticHermiteSpline : public Spline<5> { public: /** * Constructs a quintic hermite spline with the specified control vectors. diff --git a/wpimath/src/main/native/include/frc/spline/SplineHelper.h b/wpimath/src/main/native/include/frc/spline/SplineHelper.h index 4af3a8a9f8..008224e961 100644 --- a/wpimath/src/main/native/include/frc/spline/SplineHelper.h +++ b/wpimath/src/main/native/include/frc/spline/SplineHelper.h @@ -7,6 +7,7 @@ #include #include +#include #include #include "frc/spline/CubicHermiteSpline.h" @@ -17,7 +18,7 @@ namespace frc { * Helper class that is used to generate cubic and quintic splines from user * provided waypoints. */ -class SplineHelper { +class WPILIB_DLLEXPORT SplineHelper { public: /** * Returns 2 cubic control vectors from a set of exterior waypoints and diff --git a/wpimath/src/main/native/include/frc/spline/SplineParameterizer.h b/wpimath/src/main/native/include/frc/spline/SplineParameterizer.h index b174b53748..0720cd1c7f 100644 --- a/wpimath/src/main/native/include/frc/spline/SplineParameterizer.h +++ b/wpimath/src/main/native/include/frc/spline/SplineParameterizer.h @@ -33,6 +33,8 @@ #include #include +#include + #include "frc/spline/Spline.h" #include "units/angle.h" #include "units/curvature.h" @@ -44,7 +46,7 @@ namespace frc { /** * Class used to parameterize a spline by its arc length. */ -class SplineParameterizer { +class WPILIB_DLLEXPORT SplineParameterizer { public: using PoseWithCurvature = std::pair; diff --git a/wpimath/src/main/native/include/frc/system/plant/DCMotor.h b/wpimath/src/main/native/include/frc/system/plant/DCMotor.h index efb7174bb5..a519b0e891 100644 --- a/wpimath/src/main/native/include/frc/system/plant/DCMotor.h +++ b/wpimath/src/main/native/include/frc/system/plant/DCMotor.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "units/angular_velocity.h" #include "units/current.h" #include "units/impedance.h" @@ -15,7 +17,7 @@ namespace frc { /** * Holds the constants for a DC motor. */ -class DCMotor { +class WPILIB_DLLEXPORT DCMotor { public: using radians_per_second_per_volt_t = units::unit_t + #include "frc/system/LinearSystem.h" #include "frc/system/plant/DCMotor.h" #include "units/acceleration.h" @@ -16,7 +17,7 @@ #include "units/voltage.h" namespace frc { -class LinearSystemId { +class WPILIB_DLLEXPORT LinearSystemId { public: template using Velocity_t = units::unit_t< diff --git a/wpimath/src/main/native/include/frc/trajectory/Trajectory.h b/wpimath/src/main/native/include/frc/trajectory/Trajectory.h index 580f806af7..2fad345f02 100644 --- a/wpimath/src/main/native/include/frc/trajectory/Trajectory.h +++ b/wpimath/src/main/native/include/frc/trajectory/Trajectory.h @@ -6,6 +6,8 @@ #include +#include + #include "frc/geometry/Pose2d.h" #include "frc/geometry/Transform2d.h" #include "units/acceleration.h" @@ -23,12 +25,12 @@ namespace frc { * various States that represent the pose, curvature, time elapsed, velocity, * and acceleration at that point. */ -class Trajectory { +class WPILIB_DLLEXPORT Trajectory { public: /** * Represents one point on the trajectory. */ - struct State { + struct WPILIB_DLLEXPORT State { // The time elapsed since the beginning of the trajectory. units::second_t t = 0_s; @@ -171,8 +173,10 @@ class Trajectory { } }; +WPILIB_DLLEXPORT void to_json(wpi::json& json, const Trajectory::State& state); +WPILIB_DLLEXPORT void from_json(const wpi::json& json, Trajectory::State& state); } // namespace frc diff --git a/wpimath/src/main/native/include/frc/trajectory/TrajectoryConfig.h b/wpimath/src/main/native/include/frc/trajectory/TrajectoryConfig.h index 4e3f5710dd..b1a0b5260a 100644 --- a/wpimath/src/main/native/include/frc/trajectory/TrajectoryConfig.h +++ b/wpimath/src/main/native/include/frc/trajectory/TrajectoryConfig.h @@ -8,6 +8,8 @@ #include #include +#include + #include "frc/kinematics/DifferentialDriveKinematics.h" #include "frc/kinematics/MecanumDriveKinematics.h" #include "frc/kinematics/SwerveDriveKinematics.h" @@ -29,7 +31,7 @@ namespace frc { * have been defaulted to reasonable values (0, 0, {}, false). These values can * be changed via the SetXXX methods. */ -class TrajectoryConfig { +class WPILIB_DLLEXPORT TrajectoryConfig { public: /** * Constructs a config object. diff --git a/wpimath/src/main/native/include/frc/trajectory/TrajectoryGenerator.h b/wpimath/src/main/native/include/frc/trajectory/TrajectoryGenerator.h index 9908a241d1..84ec0e0ad4 100644 --- a/wpimath/src/main/native/include/frc/trajectory/TrajectoryGenerator.h +++ b/wpimath/src/main/native/include/frc/trajectory/TrajectoryGenerator.h @@ -9,6 +9,8 @@ #include #include +#include + #include "frc/spline/SplineParameterizer.h" #include "frc/trajectory/Trajectory.h" #include "frc/trajectory/TrajectoryConfig.h" @@ -19,7 +21,7 @@ namespace frc { /** * Helper class used to generate trajectories with various constraints. */ -class TrajectoryGenerator { +class WPILIB_DLLEXPORT TrajectoryGenerator { public: using PoseWithCurvature = std::pair; diff --git a/wpimath/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h b/wpimath/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h index f7fc904f02..eea1c078f3 100644 --- a/wpimath/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h +++ b/wpimath/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h @@ -32,6 +32,8 @@ #include #include +#include + #include "frc/trajectory/Trajectory.h" #include "frc/trajectory/constraint/TrajectoryConstraint.h" @@ -39,7 +41,7 @@ namespace frc { /** * Class used to parameterize a trajectory by time. */ -class TrajectoryParameterizer { +class WPILIB_DLLEXPORT TrajectoryParameterizer { public: using PoseWithCurvature = std::pair; diff --git a/wpimath/src/main/native/include/frc/trajectory/TrajectoryUtil.h b/wpimath/src/main/native/include/frc/trajectory/TrajectoryUtil.h index 612e8b2b6e..308502b271 100644 --- a/wpimath/src/main/native/include/frc/trajectory/TrajectoryUtil.h +++ b/wpimath/src/main/native/include/frc/trajectory/TrajectoryUtil.h @@ -7,10 +7,12 @@ #include #include +#include + #include "frc/trajectory/Trajectory.h" namespace frc { -class TrajectoryUtil { +class WPILIB_DLLEXPORT TrajectoryUtil { public: TrajectoryUtil() = delete; diff --git a/wpimath/src/main/native/include/frc/trajectory/constraint/CentripetalAccelerationConstraint.h b/wpimath/src/main/native/include/frc/trajectory/constraint/CentripetalAccelerationConstraint.h index 1b57267287..5ef15a4428 100644 --- a/wpimath/src/main/native/include/frc/trajectory/constraint/CentripetalAccelerationConstraint.h +++ b/wpimath/src/main/native/include/frc/trajectory/constraint/CentripetalAccelerationConstraint.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "frc/trajectory/constraint/TrajectoryConstraint.h" #include "units/acceleration.h" #include "units/curvature.h" @@ -20,7 +22,8 @@ namespace frc { * robot to slow down around tight turns, making it easier to track trajectories * with sharp turns. */ -class CentripetalAccelerationConstraint : public TrajectoryConstraint { +class WPILIB_DLLEXPORT CentripetalAccelerationConstraint + : public TrajectoryConstraint { public: explicit CentripetalAccelerationConstraint( units::meters_per_second_squared_t maxCentripetalAcceleration); diff --git a/wpimath/src/main/native/include/frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h b/wpimath/src/main/native/include/frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h index 01fd05fa8e..ad643bfa42 100644 --- a/wpimath/src/main/native/include/frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h +++ b/wpimath/src/main/native/include/frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "frc/kinematics/DifferentialDriveKinematics.h" #include "frc/trajectory/constraint/TrajectoryConstraint.h" #include "units/velocity.h" @@ -15,7 +17,8 @@ namespace frc { * commanded velocities for both sides of the drivetrain stay below a certain * limit. */ -class DifferentialDriveKinematicsConstraint : public TrajectoryConstraint { +class WPILIB_DLLEXPORT DifferentialDriveKinematicsConstraint + : public TrajectoryConstraint { public: DifferentialDriveKinematicsConstraint( const DifferentialDriveKinematics& kinematics, diff --git a/wpimath/src/main/native/include/frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h b/wpimath/src/main/native/include/frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h index 5d7192831e..06d0e50078 100644 --- a/wpimath/src/main/native/include/frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h +++ b/wpimath/src/main/native/include/frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "frc/controller/SimpleMotorFeedforward.h" #include "frc/kinematics/DifferentialDriveKinematics.h" #include "frc/trajectory/constraint/TrajectoryConstraint.h" @@ -17,7 +19,8 @@ namespace frc { * acceleration of any wheel of the robot while following the trajectory is * never higher than what can be achieved with the given maximum voltage. */ -class DifferentialDriveVoltageConstraint : public TrajectoryConstraint { +class WPILIB_DLLEXPORT DifferentialDriveVoltageConstraint + : public TrajectoryConstraint { public: /** * Creates a new DifferentialDriveVoltageConstraint. diff --git a/wpimath/src/main/native/include/frc/trajectory/constraint/MaxVelocityConstraint.h b/wpimath/src/main/native/include/frc/trajectory/constraint/MaxVelocityConstraint.h index f80b6fd83f..b7375d5d6d 100644 --- a/wpimath/src/main/native/include/frc/trajectory/constraint/MaxVelocityConstraint.h +++ b/wpimath/src/main/native/include/frc/trajectory/constraint/MaxVelocityConstraint.h @@ -4,6 +4,8 @@ #pragma once +#include + #include "frc/trajectory/constraint/TrajectoryConstraint.h" #include "units/math.h" #include "units/velocity.h" @@ -14,26 +16,21 @@ namespace frc { * with the EllipticalRegionConstraint or RectangularRegionConstraint to enforce * a max velocity within a region. */ -class MaxVelocityConstraint : public TrajectoryConstraint { +class WPILIB_DLLEXPORT MaxVelocityConstraint : public TrajectoryConstraint { public: /** * Constructs a new MaxVelocityConstraint. * * @param maxVelocity The max velocity. */ - explicit MaxVelocityConstraint(units::meters_per_second_t maxVelocity) - : m_maxVelocity(units::math::abs(maxVelocity)) {} + explicit MaxVelocityConstraint(units::meters_per_second_t maxVelocity); units::meters_per_second_t MaxVelocity( const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const override { - return m_maxVelocity; - } + units::meters_per_second_t velocity) const override; MinMax MinMaxAcceleration(const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t speed) const override { - return {}; - } + units::meters_per_second_t speed) const override; private: units::meters_per_second_t m_maxVelocity; diff --git a/wpimath/src/main/native/include/frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h b/wpimath/src/main/native/include/frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h index 18bd2a90e6..816d8ef405 100644 --- a/wpimath/src/main/native/include/frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h +++ b/wpimath/src/main/native/include/frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h @@ -6,6 +6,8 @@ #include +#include + #include "frc/kinematics/MecanumDriveKinematics.h" #include "frc/trajectory/constraint/TrajectoryConstraint.h" #include "units/velocity.h" @@ -17,7 +19,8 @@ namespace frc { * commanded velocities for wheels of the drivetrain stay below a certain * limit. */ -class MecanumDriveKinematicsConstraint : public TrajectoryConstraint { +class WPILIB_DLLEXPORT MecanumDriveKinematicsConstraint + : public TrajectoryConstraint { public: MecanumDriveKinematicsConstraint(const MecanumDriveKinematics& kinematics, units::meters_per_second_t maxSpeed); diff --git a/wpimath/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.h b/wpimath/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.h index 9556735a7f..67e9fc9272 100644 --- a/wpimath/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.h +++ b/wpimath/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.h @@ -12,13 +12,12 @@ namespace frc { -template - /** * A class that enforces constraints on the swerve drive kinematics. * This can be used to ensure that the trajectory is constructed so that the * commanded velocities of the wheels stay below a certain limit. */ +template class SwerveDriveKinematicsConstraint : public TrajectoryConstraint { public: SwerveDriveKinematicsConstraint( diff --git a/wpimath/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.inc b/wpimath/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.inc index 8100dffdc5..1a1e4b869a 100644 --- a/wpimath/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.inc +++ b/wpimath/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.inc @@ -10,12 +10,6 @@ namespace frc { template - -/** - * A class that enforces constraints on the swerve drive kinematics. - * This can be used to ensure that the trajectory is constructed so that the - * commanded velocities of the wheels stay below a certain limit. - */ SwerveDriveKinematicsConstraint::SwerveDriveKinematicsConstraint( const frc::SwerveDriveKinematics& kinematics, units::meters_per_second_t maxSpeed) diff --git a/wpimath/src/main/native/include/frc/trajectory/constraint/TrajectoryConstraint.h b/wpimath/src/main/native/include/frc/trajectory/constraint/TrajectoryConstraint.h index af08b71d69..47ca820c52 100644 --- a/wpimath/src/main/native/include/frc/trajectory/constraint/TrajectoryConstraint.h +++ b/wpimath/src/main/native/include/frc/trajectory/constraint/TrajectoryConstraint.h @@ -6,6 +6,8 @@ #include +#include + #include "frc/geometry/Pose2d.h" #include "frc/spline/Spline.h" #include "units/acceleration.h" @@ -17,7 +19,7 @@ namespace frc { * An interface for defining user-defined velocity and acceleration constraints * while generating trajectories. */ -class TrajectoryConstraint { +class WPILIB_DLLEXPORT TrajectoryConstraint { public: TrajectoryConstraint() = default; diff --git a/wpimath/src/main/native/include/units/base.h b/wpimath/src/main/native/include/units/base.h index 7c6244eb02..f2d45cf9b5 100644 --- a/wpimath/src/main/native/include/units/base.h +++ b/wpimath/src/main/native/include/units/base.h @@ -84,6 +84,8 @@ #include #endif +#include + //------------------------------ // STRING FORMATTER //------------------------------ diff --git a/wpimath/src/main/native/include/wpimath/MathShared.h b/wpimath/src/main/native/include/wpimath/MathShared.h index 3a66fa8c2d..f4a1795c31 100644 --- a/wpimath/src/main/native/include/wpimath/MathShared.h +++ b/wpimath/src/main/native/include/wpimath/MathShared.h @@ -7,6 +7,7 @@ #include #include +#include namespace wpi::math { @@ -23,7 +24,7 @@ enum class MathUsageId { kController_ProfiledPIDController, }; -class MathShared { +class WPILIB_DLLEXPORT MathShared { public: virtual ~MathShared() = default; virtual void ReportErrorV(fmt::string_view format, fmt::format_args args) = 0; @@ -42,7 +43,7 @@ class MathShared { } }; -class MathSharedStore { +class WPILIB_DLLEXPORT MathSharedStore { public: static MathShared& GetMathShared(); diff --git a/wpiutil/src/main/native/include/wpi/SymbolExports.h b/wpiutil/src/main/native/include/wpi/SymbolExports.h new file mode 100644 index 0000000000..4e84825863 --- /dev/null +++ b/wpiutil/src/main/native/include/wpi/SymbolExports.h @@ -0,0 +1,23 @@ +// 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 + +#ifdef _WIN32 +#pragma warning(disable : 4251) + +#ifdef WPILIB_EXPORTS +#ifdef __GNUC__ +#define WPILIB_DLLEXPORT __attribute__((dllexport)) +#else +#define WPILIB_DLLEXPORT __declspec(dllexport) +#endif + +#else +#define WPILIB_DLLEXPORT +#endif + +#else +#define WPILIB_DLLEXPORT __attribute__((visibility("default"))) +#endif diff --git a/wpiutil/src/main/native/include/wpi/sendable/Sendable.h b/wpiutil/src/main/native/include/wpi/sendable/Sendable.h index 84ebc06b2d..d587c3c78d 100644 --- a/wpiutil/src/main/native/include/wpi/sendable/Sendable.h +++ b/wpiutil/src/main/native/include/wpi/sendable/Sendable.h @@ -4,6 +4,8 @@ #pragma once +#include "wpi/SymbolExports.h" + namespace wpi { class SendableBuilder; @@ -11,7 +13,7 @@ class SendableBuilder; /** * Interface for Sendable objects. */ -class Sendable { +class WPILIB_DLLEXPORT Sendable { public: virtual ~Sendable() = default;