40std::function<Vectord<States>(
const Vectord<States>&,
const Vectord<States>&)>
42 return [=](
auto a,
auto b) {
43 return AngleResidual<States>(a,
b, angleStateIdx);
73std::function<Vectord<States>(
const Vectord<States>&,
const Vectord<States>&)>
75 return [=](
auto a,
auto b) {
return AngleAdd<States>(a,
b, angleStateIdx); };
89template <
int CovDim,
int States>
93 double sumSin = (sigmas.row(angleStatesIdx).unaryExpr([](
auto it) {
98 double sumCos = (sigmas.row(angleStatesIdx).unaryExpr([](
auto it) {
105 ret[angleStatesIdx] =
std::atan2(sumSin, sumCos);
118template <
int CovDim,
int States>
119std::function<Vectord<CovDim>(
const Matrixd<CovDim, 2 * States + 1>&,
120 const Vectord<2 * States + 1>&)>
122 return [=](
auto sigmas,
auto Wm) {
123 return AngleMean<CovDim, States>(sigmas, Wm, angleStateIdx);
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
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: AprilTagPoseEstimator.h:15
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:166
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.