The UKF test was calling `.value()` on an implicit
`units::millisecond_t` type assuming it was `units::second_t`.
I normalized the rest of the dt declarations while I was at it.
I upgraded all plugins I could see except org.ysb33r.doxygen. 2.0 made
breaking changes, and I couldn't figure out how to migrate.
Most of the changes are for suppressing new linter purification rites.
Adds methods to compute the dot and cross products between Translation2ds and Translation3ds, as well as methods to compute the square of Distance and Norm, which allows avoiding some calls to sqrt in many cases.
Co-authored-by: Tyler Veness <calcmogul@gmail.com>
Ensures java deprecated notation is paired with javadoc and vice versa.
Adds javadoc deprecation for MecanumControllerCommand, ArmFeedForward,
ElevatorFeedforward, and MecanumDriveMotorVoltages
Fixes#7736
Supersedes #7737
Co-authored-by: Joseph Eng <91924258+KangarooKoala@users.noreply.github.com>
A noteworthy change is the replacement of the `dp.startswith(os.path.join(".", "subdir"))` pattern. pathlib doesn't offer something with similar semantics besides `match` and `full_match`, so there's now a helper function that replicates the behavior.
Other notable changes include the addition of type annotations to ensure code correctness, using == to check file names instead of `endswith` for clarity (`endswith` is still used to check extensions), manual walking and copying being refactored in googletest, json, memory, nanopb, protobuf, and sleipnir to use `walk_cwd_and_copy_if`, and matching functions being shortened to the point where they can just be inlined into the lambda.
Co-authored-by: Tyler Veness <calcmogul@gmail.com>
Co-authored-by: David Vo <auscompgeek@users.noreply.github.com>
Reduces nesting by returning when the value is within the deadband.
Adjusts the algorithm to handle large values of maxMagnitude naturally (instead of needing a separate check).
Reformats the math comments.
Throughout the code the state sqrt covariance S and innovation covariance Sy are maintained as upper triangular cholesky factors of those covariance matrices. The original paper defines P=S*S', so S should be lower triangular. The functions in the paper reflect this. In the code implementation, the sqrt covariance matrices are upper triangular, but the algorithm expects them to be lower triangular.
This bug was likely missed because the incorrect version of the filter is able to converge for some systems where all the states are observed, and the test case is set up such that all states are observed.
To fix the bug, a couple things needed to be changed:
all instances of rankUpdate() needed to be changed to use the lower triangular cholesky factor,
In the unscented transform, when S is found via QR decomposition, we need to take the transpose because R is upper triangular,
P() and SetP() functions need to be modified to be P=S*S' instead of P=S'*S, and P.llt().matrixL() instead of P.llt().matrixU() respectively.
Each part of the algorithm has also had the comments changed to clarify exactly which equation from the paper it implements.
Co-authored-by: Tyler Veness <calcmogul@gmail.com>
Small values of kₐ make the iterative solver ill-conditioned. This
change reverts to the constant-acceleration feedforward in that case. It
gives _very_ bad results (hence why we added the iterative solver in the
first place), but it's better than hanging.
```
TEST(ArmFeedforwardTest, CalculateIllConditioned) {
constexpr auto Ks = 0.5_V;
constexpr auto Kv = 20_V / 1_rad_per_s;
constexpr auto Ka = 1e-2_V / 1_rad_per_s_sq;
constexpr auto Kg = 0_V;
frc::ArmFeedforward armFF{Ks, Kg, Kv, Ka};
// Calculate(currentAngle, currentVelocity, nextAngle, dt)
CalculateAndSimulate(armFF, 0_rad, 0_rad_per_s, 2_rad_per_s, 20_ms);
}
```
This produces 1 V and doesn't accelerate the system at all. Using
nextVelocity instead of currentVelocity in the feedforward outputs 41 V
and still only accelerates to 0.4 rad/s of the requested 2 rad/s.
I picked the kₐ cutoff by increasing kₐ until the iterative solver
started converging.
Fixes#7743.