mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Refactor StateSpaceUtil into separate files (#8421)
* Moved makeWhiteNoiseVector() to random.Normal.normal() * Moved isControllable() and isDetectable() to system.LinearSystemUtil * Renamed makeCostMatrix() to costMatrix() (Java) * Renamed makeCovarianceMatrix() to covarianceMatrix() (Java) * Renamed MakeCostMatrix() to CostMatrix() (C++) * Renamed MakeCovMatrix() to CovarianceMatrix() (C++) * Removed deprecated poseTo3dVector(), poseTo4dVector(), poseToVector() * Removed clampInputMaxMagnitude() * We don't use it, and Eigen has this functionality built in via `u = u.array().min(u_max.array()).max(u_min.array());` * Simplified implementation of desaturateInputVector()
This commit is contained in:
@@ -5,7 +5,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "wpi/math/geometry/Pose2d.hpp"
|
||||
#include "wpi/math/util/StateSpaceUtil.hpp"
|
||||
#include "wpi/math/random/Normal.hpp"
|
||||
|
||||
/**
|
||||
* This dummy class represents a global measurement sensor, such as a computer
|
||||
@@ -15,7 +15,7 @@ class ExampleGlobalMeasurementSensor {
|
||||
public:
|
||||
static wpi::math::Pose2d GetEstimatedGlobalPose(
|
||||
const wpi::math::Pose2d& estimatedRobotPose) {
|
||||
auto randVec = wpi::math::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
|
||||
auto randVec = wpi::math::Normal(0.1, 0.1, 0.1);
|
||||
return wpi::math::Pose2d{
|
||||
estimatedRobotPose.X() + wpi::units::meter_t{randVec(0)},
|
||||
estimatedRobotPose.Y() + wpi::units::meter_t{randVec(1)},
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "wpi/math/geometry/Pose2d.hpp"
|
||||
#include "wpi/math/util/StateSpaceUtil.hpp"
|
||||
#include "wpi/math/random/Normal.hpp"
|
||||
|
||||
/**
|
||||
* This dummy class represents a global measurement sensor, such as a computer
|
||||
@@ -15,7 +15,7 @@ class ExampleGlobalMeasurementSensor {
|
||||
public:
|
||||
static wpi::math::Pose2d GetEstimatedGlobalPose(
|
||||
const wpi::math::Pose2d& estimatedRobotPose) {
|
||||
auto randVec = wpi::math::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
|
||||
auto randVec = wpi::math::Normal(0.1, 0.1, 0.1);
|
||||
return wpi::math::Pose2d{
|
||||
estimatedRobotPose.X() + wpi::units::meter_t{randVec(0)},
|
||||
estimatedRobotPose.Y() + wpi::units::meter_t{randVec(1)},
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "wpi/math/geometry/Pose2d.hpp"
|
||||
#include "wpi/math/util/StateSpaceUtil.hpp"
|
||||
#include "wpi/math/random/Normal.hpp"
|
||||
|
||||
/**
|
||||
* This dummy class represents a global measurement sensor, such as a computer
|
||||
@@ -15,7 +15,7 @@ class ExampleGlobalMeasurementSensor {
|
||||
public:
|
||||
static wpi::math::Pose2d GetEstimatedGlobalPose(
|
||||
const wpi::math::Pose2d& estimatedRobotPose) {
|
||||
auto randVec = wpi::math::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
|
||||
auto randVec = wpi::math::Normal(0.1, 0.1, 0.1);
|
||||
return wpi::math::Pose2d{
|
||||
estimatedRobotPose.X() + wpi::units::meter_t{randVec(0)},
|
||||
estimatedRobotPose.Y() + wpi::units::meter_t{randVec(1)},
|
||||
|
||||
Reference in New Issue
Block a user