WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
AngleStatistics.hpp File Reference
#include <functional>
#include <numbers>
#include "wpi/math/linalg/EigenCore.hpp"
#include "wpi/math/util/MathUtil.hpp"

Go to the source code of this file.

Namespaces

namespace  wpi
namespace  wpi::math

Functions

template<int States>
Vectord< States > wpi::math::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.
template<int States>
std::function< Vectord< States >(const Vectord< States > &, const Vectord< States > &)> wpi::math::AngleResidual (int angleStateIdx)
 Returns a function that subtracts two vectors while normalizing the resulting value in the selected row as if it were an angle.
template<int States>
Vectord< States > wpi::math::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.
template<int States>
std::function< Vectord< States >(const Vectord< States > &, const Vectord< States > &)> wpi::math::AngleAdd (int angleStateIdx)
 Returns a function that adds two vectors while normalizing the resulting value in the selected row as an angle.
template<int CovDim, int NumSigmas>
Vectord< CovDim > wpi::math::AngleMean (const Matrixd< CovDim, NumSigmas > &sigmas, const Vectord< NumSigmas > &Wm, int angleStatesIdx)
 Computes the mean of sigmas with the weights Wm while computing a special angle mean for a select row.
template<int CovDim, int NumSigmas>
std::function< Vectord< CovDim >(const Matrixd< CovDim, NumSigmas > &, const Vectord< NumSigmas > &)> wpi::math::AngleMean (int angleStateIdx)
 Returns a function that computes the mean of sigmas with the weights Wm while computing a special angle mean for a select row.