Skip to content

Commit 05c7fd9

Browse files
authored
[wpimath] Make various classes constexpr (#7237)
1 parent 0c824bd commit 05c7fd9

21 files changed

+235
-307
lines changed

wpimath/src/main/native/cpp/ComputerVisionUtil.cpp

Lines changed: 0 additions & 19 deletions
This file was deleted.

wpimath/src/main/native/cpp/StateSpaceUtil.cpp

Lines changed: 0 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -6,28 +6,11 @@
66

77
namespace frc {
88

9-
Eigen::Vector3d PoseTo3dVector(const Pose2d& pose) {
10-
return Eigen::Vector3d{pose.Translation().X().value(),
11-
pose.Translation().Y().value(),
12-
pose.Rotation().Radians().value()};
13-
}
14-
15-
Eigen::Vector4d PoseTo4dVector(const Pose2d& pose) {
16-
return Eigen::Vector4d{pose.Translation().X().value(),
17-
pose.Translation().Y().value(), pose.Rotation().Cos(),
18-
pose.Rotation().Sin()};
19-
}
20-
219
template bool IsStabilizable<1, 1>(const Matrixd<1, 1>& A,
2210
const Matrixd<1, 1>& B);
2311
template bool IsStabilizable<2, 1>(const Matrixd<2, 2>& A,
2412
const Matrixd<2, 1>& B);
2513
template bool IsStabilizable<Eigen::Dynamic, Eigen::Dynamic>(
2614
const Eigen::MatrixXd& A, const Eigen::MatrixXd& B);
2715

28-
Eigen::Vector3d PoseToVector(const Pose2d& pose) {
29-
return Eigen::Vector3d{pose.X().value(), pose.Y().value(),
30-
pose.Rotation().Radians().value()};
31-
}
32-
3316
} // namespace frc

wpimath/src/main/native/cpp/kinematics/DifferentialDriveWheelSpeeds.cpp

Lines changed: 0 additions & 20 deletions
This file was deleted.

wpimath/src/main/native/cpp/kinematics/MecanumDriveWheelSpeeds.cpp

Lines changed: 0 additions & 33 deletions
This file was deleted.

wpimath/src/main/native/cpp/kinematics/SwerveModulePosition.cpp

Lines changed: 0 additions & 15 deletions
This file was deleted.

wpimath/src/main/native/cpp/kinematics/SwerveModuleState.cpp

Lines changed: 0 additions & 24 deletions
This file was deleted.

wpimath/src/main/native/include/frc/ComputerVisionUtil.h

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,12 @@ namespace frc {
3030
* @return The robot's field-relative pose.
3131
*/
3232
WPILIB_DLLEXPORT
33-
frc::Pose3d ObjectToRobotPose(const frc::Pose3d& objectInField,
34-
const frc::Transform3d& cameraToObject,
35-
const frc::Transform3d& robotToCamera);
33+
constexpr frc::Pose3d ObjectToRobotPose(const frc::Pose3d& objectInField,
34+
const frc::Transform3d& cameraToObject,
35+
const frc::Transform3d& robotToCamera) {
36+
const auto objectToCamera = cameraToObject.Inverse();
37+
const auto cameraToRobot = robotToCamera.Inverse();
38+
return objectInField + objectToCamera + cameraToRobot;
39+
}
3640

3741
} // namespace frc

wpimath/src/main/native/include/frc/MathUtil.h

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
#include <numbers>
88
#include <type_traits>
99

10+
#include <gcem.hpp>
1011
#include <wpi/SymbolExports.h>
1112

1213
#include "units/angle.h"
@@ -28,10 +29,10 @@ namespace frc {
2829
*/
2930
template <typename T>
3031
requires std::is_arithmetic_v<T> || units::traits::is_unit_t_v<T>
31-
T ApplyDeadband(T value, T deadband, T maxMagnitude = T{1.0}) {
32+
constexpr T ApplyDeadband(T value, T deadband, T maxMagnitude = T{1.0}) {
3233
T magnitude;
3334
if constexpr (std::is_arithmetic_v<T>) {
34-
magnitude = std::abs(value);
35+
magnitude = gcem::abs(value);
3536
} else {
3637
magnitude = units::math::abs(value);
3738
}

wpimath/src/main/native/include/frc/StateSpaceUtil.h

Lines changed: 18 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -209,7 +209,11 @@ Vectord<N> MakeWhiteNoiseVector(const std::array<double, N>& stdDevs) {
209209
* @return The vector.
210210
*/
211211
WPILIB_DLLEXPORT
212-
Eigen::Vector3d PoseTo3dVector(const Pose2d& pose);
212+
constexpr Eigen::Vector3d PoseTo3dVector(const Pose2d& pose) {
213+
return Eigen::Vector3d{{pose.Translation().X().value(),
214+
pose.Translation().Y().value(),
215+
pose.Rotation().Radians().value()}};
216+
}
213217

214218
/**
215219
* Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)].
@@ -219,7 +223,11 @@ Eigen::Vector3d PoseTo3dVector(const Pose2d& pose);
219223
* @return The vector.
220224
*/
221225
WPILIB_DLLEXPORT
222-
Eigen::Vector4d PoseTo4dVector(const Pose2d& pose);
226+
constexpr Eigen::Vector4d PoseTo4dVector(const Pose2d& pose) {
227+
return Eigen::Vector4d{{pose.Translation().X().value(),
228+
pose.Translation().Y().value(), pose.Rotation().Cos(),
229+
pose.Rotation().Sin()}};
230+
}
223231

224232
/**
225233
* Returns true if (A, B) is a stabilizable pair.
@@ -306,7 +314,10 @@ bool IsDetectable(const Matrixd<States, States>& A,
306314
* @return The vector.
307315
*/
308316
WPILIB_DLLEXPORT
309-
Eigen::Vector3d PoseToVector(const Pose2d& pose);
317+
constexpr Eigen::Vector3d PoseToVector(const Pose2d& pose) {
318+
return Eigen::Vector3d{
319+
{pose.X().value(), pose.Y().value(), pose.Rotation().Radians().value()}};
320+
}
310321

311322
/**
312323
* Clamps input vector between system's minimum and maximum allowable input.
@@ -318,12 +329,12 @@ Eigen::Vector3d PoseToVector(const Pose2d& pose);
318329
* @return Clamped input vector.
319330
*/
320331
template <int Inputs>
321-
Vectord<Inputs> ClampInputMaxMagnitude(const Vectord<Inputs>& u,
322-
const Vectord<Inputs>& umin,
323-
const Vectord<Inputs>& umax) {
332+
constexpr Vectord<Inputs> ClampInputMaxMagnitude(const Vectord<Inputs>& u,
333+
const Vectord<Inputs>& umin,
334+
const Vectord<Inputs>& umax) {
324335
Vectord<Inputs> result;
325336
for (int i = 0; i < Inputs; ++i) {
326-
result(i) = std::clamp(u(i), umin(i), umax(i));
337+
result.coeffRef(i) = std::clamp(u.coeff(i), umin.coeff(i), umax.coeff(i));
327338
}
328339
return result;
329340
}

wpimath/src/main/native/include/frc/filter/LinearFilter.h

Lines changed: 27 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -5,13 +5,14 @@
55
#pragma once
66

77
#include <algorithm>
8-
#include <cmath>
98
#include <initializer_list>
109
#include <span>
1110
#include <stdexcept>
11+
#include <type_traits>
1212
#include <vector>
1313

1414
#include <Eigen/QR>
15+
#include <gcem.hpp>
1516
#include <wpi/array.h>
1617
#include <wpi/circular_buffer.h>
1718

@@ -80,7 +81,8 @@ class LinearFilter {
8081
* @param ffGains The "feedforward" or FIR gains.
8182
* @param fbGains The "feedback" or IIR gains.
8283
*/
83-
LinearFilter(std::span<const double> ffGains, std::span<const double> fbGains)
84+
constexpr LinearFilter(std::span<const double> ffGains,
85+
std::span<const double> fbGains)
8486
: m_inputs(ffGains.size()),
8587
m_outputs(fbGains.size()),
8688
m_inputGains(ffGains.begin(), ffGains.end()),
@@ -92,10 +94,11 @@ class LinearFilter {
9294
m_outputs.emplace_front(0.0);
9395
}
9496

95-
static int instances = 0;
96-
instances++;
97-
wpi::math::MathSharedStore::ReportUsage(
98-
wpi::math::MathUsageId::kFilter_Linear, instances);
97+
if (!std::is_constant_evaluated()) {
98+
++instances;
99+
wpi::math::MathSharedStore::ReportUsage(
100+
wpi::math::MathUsageId::kFilter_Linear, instances);
101+
}
99102
}
100103

101104
/**
@@ -104,8 +107,8 @@ class LinearFilter {
104107
* @param ffGains The "feedforward" or FIR gains.
105108
* @param fbGains The "feedback" or IIR gains.
106109
*/
107-
LinearFilter(std::initializer_list<double> ffGains,
108-
std::initializer_list<double> fbGains)
110+
constexpr LinearFilter(std::initializer_list<double> ffGains,
111+
std::initializer_list<double> fbGains)
109112
: LinearFilter({ffGains.begin(), ffGains.end()},
110113
{fbGains.begin(), fbGains.end()}) {}
111114

@@ -124,9 +127,9 @@ class LinearFilter {
124127
* @param period The period in seconds between samples taken by the
125128
* user.
126129
*/
127-
static LinearFilter<T> SinglePoleIIR(double timeConstant,
128-
units::second_t period) {
129-
double gain = std::exp(-period.value() / timeConstant);
130+
static constexpr LinearFilter<T> SinglePoleIIR(double timeConstant,
131+
units::second_t period) {
132+
double gain = gcem::exp(-period.value() / timeConstant);
130133
return LinearFilter({1.0 - gain}, {-gain});
131134
}
132135

@@ -144,8 +147,9 @@ class LinearFilter {
144147
* @param period The period in seconds between samples taken by the
145148
* user.
146149
*/
147-
static LinearFilter<T> HighPass(double timeConstant, units::second_t period) {
148-
double gain = std::exp(-period.value() / timeConstant);
150+
static constexpr LinearFilter<T> HighPass(double timeConstant,
151+
units::second_t period) {
152+
double gain = gcem::exp(-period.value() / timeConstant);
149153
return LinearFilter({gain, -gain}, {-gain});
150154
}
151155

@@ -213,7 +217,7 @@ class LinearFilter {
213217
Matrixd<Samples, Samples> S;
214218
for (int row = 0; row < Samples; ++row) {
215219
for (int col = 0; col < Samples; ++col) {
216-
S(row, col) = std::pow(stencil[col], row);
220+
S(row, col) = gcem::pow(stencil[col], row);
217221
}
218222
}
219223

@@ -224,7 +228,7 @@ class LinearFilter {
224228
}
225229

226230
Vectord<Samples> a =
227-
S.householderQr().solve(d) / std::pow(period.value(), Derivative);
231+
S.householderQr().solve(d) / gcem::pow(period.value(), Derivative);
228232

229233
// Reverse gains list
230234
std::vector<double> ffGains;
@@ -266,7 +270,7 @@ class LinearFilter {
266270
/**
267271
* Reset the filter state.
268272
*/
269-
void Reset() {
273+
constexpr void Reset() {
270274
std::fill(m_inputs.begin(), m_inputs.end(), T{0.0});
271275
std::fill(m_outputs.begin(), m_outputs.end(), T{0.0});
272276
}
@@ -321,7 +325,8 @@ class LinearFilter {
321325
* @throws std::runtime_error if size of inputBuffer or outputBuffer does not
322326
* match the size of ffGains and fbGains provided in the constructor.
323327
*/
324-
void Reset(std::span<const T> inputBuffer, std::span<const T> outputBuffer) {
328+
constexpr void Reset(std::span<const T> inputBuffer,
329+
std::span<const T> outputBuffer) {
325330
// Clear buffers
326331
Reset();
327332

@@ -346,7 +351,7 @@ class LinearFilter {
346351
*
347352
* @return The filtered value at this step
348353
*/
349-
T Calculate(T input) {
354+
constexpr T Calculate(T input) {
350355
T retVal{0.0};
351356

352357
// Rotate the inputs
@@ -376,7 +381,7 @@ class LinearFilter {
376381
*
377382
* @return The last value.
378383
*/
379-
T LastValue() const { return m_lastOutput; }
384+
constexpr T LastValue() const { return m_lastOutput; }
380385

381386
private:
382387
wpi::circular_buffer<T> m_inputs;
@@ -385,6 +390,9 @@ class LinearFilter {
385390
std::vector<double> m_outputGains;
386391
T m_lastOutput{0.0};
387392

393+
// Usage reporting instances
394+
inline static int instances = 0;
395+
388396
/**
389397
* Factorial of n.
390398
*

0 commit comments

Comments
 (0)