WPILibC++ 2023.4.3
AngleStatistics.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <numbers>
8
9#include "frc/EigenCore.h"
10#include "frc/MathUtil.h"
11
12namespace frc {
13
14/**
15 * Subtracts a and b while normalizing the resulting value in the selected row
16 * as if it were an angle.
17 *
18 * @tparam States The number of states.
19 * @param a A vector to subtract from.
20 * @param b A vector to subtract with.
21 * @param angleStateIdx The row containing angles to be normalized.
22 */
23template <int States>
25 const Vectord<States>& b, int angleStateIdx) {
26 Vectord<States> ret = a - b;
27 ret[angleStateIdx] =
28 AngleModulus(units::radian_t{ret[angleStateIdx]}).value();
29 return ret;
30}
31
32/**
33 * Returns a function that subtracts two vectors while normalizing the resulting
34 * value in the selected row as if it were an angle.
35 *
36 * @tparam States The number of states.
37 * @param angleStateIdx The row containing angles to be normalized.
38 */
39template <int States>
40std::function<Vectord<States>(const Vectord<States>&, const Vectord<States>&)>
41AngleResidual(int angleStateIdx) {
42 return [=](auto a, auto b) {
43 return AngleResidual<States>(a, b, angleStateIdx);
44 };
45}
46
47/**
48 * Adds a and b while normalizing the resulting value in the selected row as an
49 * angle.
50 *
51 * @tparam States The number of states.
52 * @param a A vector to add with.
53 * @param b A vector to add with.
54 * @param angleStateIdx The row containing angles to be normalized.
55 */
56template <int States>
58 int angleStateIdx) {
59 Vectord<States> ret = a + b;
60 ret[angleStateIdx] =
61 InputModulus(ret[angleStateIdx], -std::numbers::pi, std::numbers::pi);
62 return ret;
63}
64
65/**
66 * Returns a function that adds two vectors while normalizing the resulting
67 * value in the selected row as an angle.
68 *
69 * @tparam States The number of states.
70 * @param angleStateIdx The row containing angles to be normalized.
71 */
72template <int States>
73std::function<Vectord<States>(const Vectord<States>&, const Vectord<States>&)>
74AngleAdd(int angleStateIdx) {
75 return [=](auto a, auto b) { return AngleAdd<States>(a, b, angleStateIdx); };
76}
77
78/**
79 * Computes the mean of sigmas with the weights Wm while computing a special
80 * angle mean for a select row.
81 *
82 * @tparam CovDim Dimension of covariance of sigma points after passing through
83 * the transform.
84 * @tparam States The number of states.
85 * @param sigmas Sigma points.
86 * @param Wm Weights for the mean.
87 * @param angleStatesIdx The row containing the angles.
88 */
89template <int CovDim, int States>
92 int angleStatesIdx) {
93 double sumSin = (sigmas.row(angleStatesIdx).unaryExpr([](auto it) {
94 return std::sin(it);
95 }) *
96 Wm)
97 .sum();
98 double sumCos = (sigmas.row(angleStatesIdx).unaryExpr([](auto it) {
99 return std::cos(it);
100 }) *
101 Wm)
102 .sum();
103
104 Vectord<CovDim> ret = sigmas * Wm;
105 ret[angleStatesIdx] = std::atan2(sumSin, sumCos);
106 return ret;
107}
108
109/**
110 * Returns a function that computes the mean of sigmas with the weights Wm while
111 * computing a special angle mean for a select row.
112 *
113 * @tparam CovDim Dimension of covariance of sigma points after passing through
114 * the transform.
115 * @tparam States The number of states.
116 * @param angleStateIdx The row containing the angles.
117 */
118template <int CovDim, int States>
119std::function<Vectord<CovDim>(const Matrixd<CovDim, 2 * States + 1>&,
120 const Vectord<2 * States + 1>&)>
121AngleMean(int angleStateIdx) {
122 return [=](auto sigmas, auto Wm) {
123 return AngleMean<CovDim, States>(sigmas, Wm, angleStateIdx);
124 };
125}
126
127} // namespace frc
constexpr common_return_t< T1, T2 > atan2(const T1 y, const T2 x) noexcept
Compile-time two-argument arctangent function.
Definition: atan2.hpp:82
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:180
Definition: core.h:1240
dimensionless::scalar_t cos(const AngleUnit angle) noexcept
Compute cosine.
Definition: math.h:61
dimensionless::scalar_t sin(const AngleUnit angle) noexcept
Compute sine.
Definition: math.h:81
Definition: AprilTagFieldLayout.h:22
Vectord< States > AngleAdd(const Vectord< States > &a, const Vectord< States > &b, int angleStateIdx)
Adds a and b while normalizing the resulting value in the selected row as an angle.
Definition: AngleStatistics.h:57
Eigen::Vector< double, Size > Vectord
Definition: EigenCore.h:12
WPILIB_DLLEXPORT constexpr units::radian_t AngleModulus(units::radian_t angle)
Wraps an angle to the range -pi to pi radians (-180 to 180 degrees).
Definition: MathUtil.h:114
Vectord< States > AngleResidual(const Vectord< States > &a, const Vectord< States > &b, int angleStateIdx)
Subtracts a and b while normalizing the resulting value in the selected row as if it were an angle.
Definition: AngleStatistics.h:24
constexpr T InputModulus(T input, T minimumInput, T maximumInput)
Returns modulus of input.
Definition: MathUtil.h:94
Vectord< CovDim > AngleMean(const Matrixd< CovDim, 2 *States+1 > &sigmas, const Vectord< 2 *States+1 > &Wm, int angleStatesIdx)
Computes the mean of sigmas with the weights Wm while computing a special angle mean for a select row...
Definition: AngleStatistics.h:90
static constexpr const unit_t< PI > pi(1)
Ratio of a circle's circumference to its diameter.
b
Definition: data.h:44