[wpimath] Reorganize LinearSystem factories (#8468)

This commit is contained in:
Tyler Veness
2026-01-12 19:09:35 -08:00
committed by GitHub
parent 89d0759ef2
commit 00fa8361dd
108 changed files with 1808 additions and 2138 deletions

View File

@@ -7,8 +7,8 @@
#include <utility>
#include "wpi/math/random/Normal.hpp"
#include "wpi/math/system/Models.hpp"
#include "wpi/math/system/NumericalIntegration.hpp"
#include "wpi/math/system/plant/LinearSystemId.hpp"
#include "wpi/math/util/StateSpaceUtil.hpp"
#include "wpi/system/RobotController.hpp"
#include "wpi/util/MathExtras.hpp"
@@ -39,7 +39,7 @@ DifferentialDrivetrainSim::DifferentialDrivetrainSim(
wpi::units::meter_t wheelRadius, wpi::units::meter_t trackwidth,
const std::array<double, 7>& measurementStdDevs)
: DifferentialDrivetrainSim(
wpi::math::LinearSystemId::DrivetrainVelocitySystem(
wpi::math::Models::DifferentialDriveFromPhysicalConstants(
driveMotor, mass, wheelRadius, trackwidth / 2.0, J, gearing),
trackwidth, driveMotor, gearing, wheelRadius, measurementStdDevs) {}

View File

@@ -4,8 +4,8 @@
#include "wpi/simulation/ElevatorSim.hpp"
#include "wpi/math/system/Models.hpp"
#include "wpi/math/system/NumericalIntegration.hpp"
#include "wpi/math/system/plant/LinearSystemId.hpp"
#include "wpi/system/RobotController.hpp"
#include "wpi/util/MathExtras.hpp"
@@ -33,7 +33,7 @@ ElevatorSim::ElevatorSim(const wpi::math::DCMotor& gearbox, double gearing,
wpi::units::meter_t maxHeight, bool simulateGravity,
wpi::units::meter_t startingHeight,
const std::array<double, 2>& measurementStdDevs)
: ElevatorSim(wpi::math::LinearSystemId::ElevatorSystem(
: ElevatorSim(wpi::math::Models::ElevatorFromPhysicalConstants(
gearbox, carriageMass, drumRadius, gearing),
gearbox, minHeight, maxHeight, simulateGravity,
startingHeight, measurementStdDevs) {}
@@ -48,9 +48,9 @@ ElevatorSim::ElevatorSim(decltype(1_V / Velocity_t<Distance>(1)) kV,
wpi::units::meter_t maxHeight, bool simulateGravity,
wpi::units::meter_t startingHeight,
const std::array<double, 2>& measurementStdDevs)
: ElevatorSim(wpi::math::LinearSystemId::IdentifyPositionSystem(kV, kA),
gearbox, minHeight, maxHeight, simulateGravity,
startingHeight, measurementStdDevs) {}
: ElevatorSim(wpi::math::Models::ElevatorFromSysId(kV, kA), gearbox,
minHeight, maxHeight, simulateGravity, startingHeight,
measurementStdDevs) {}
void ElevatorSim::SetState(wpi::units::meter_t position,
wpi::units::meters_per_second_t velocity) {

View File

@@ -6,8 +6,8 @@
#include <cmath>
#include "wpi/math/system/Models.hpp"
#include "wpi/math/system/NumericalIntegration.hpp"
#include "wpi/math/system/plant/LinearSystemId.hpp"
#include "wpi/system/RobotController.hpp"
#include "wpi/units/voltage.hpp"
#include "wpi/util/MathExtras.hpp"
@@ -38,10 +38,11 @@ SingleJointedArmSim::SingleJointedArmSim(
wpi::units::radian_t minAngle, wpi::units::radian_t maxAngle,
bool simulateGravity, wpi::units::radian_t startingAngle,
const std::array<double, 2>& measurementStdDevs)
: SingleJointedArmSim(wpi::math::LinearSystemId::SingleJointedArmSystem(
gearbox, moi, gearing),
gearbox, gearing, armLength, minAngle, maxAngle,
simulateGravity, startingAngle, measurementStdDevs) {}
: SingleJointedArmSim(
wpi::math::Models::SingleJointedArmFromPhysicalConstants(gearbox, moi,
gearing),
gearbox, gearing, armLength, minAngle, maxAngle, simulateGravity,
startingAngle, measurementStdDevs) {}
void SingleJointedArmSim::SetState(wpi::units::radian_t angle,
wpi::units::radians_per_second_t velocity) {