[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

@@ -12,9 +12,9 @@ import org.wpilib.hardware.rotation.Encoder;
import org.wpilib.math.controller.PIDController;
import org.wpilib.math.numbers.N1;
import org.wpilib.math.numbers.N2;
import org.wpilib.math.system.DCMotor;
import org.wpilib.math.system.LinearSystem;
import org.wpilib.math.system.plant.DCMotor;
import org.wpilib.math.system.plant.LinearSystemId;
import org.wpilib.math.system.Models;
import org.wpilib.system.RobotController;
class DCMotorSimTest {
@@ -23,7 +23,8 @@ class DCMotorSimTest {
RoboRioSim.resetData();
DCMotor gearbox = DCMotor.getNEO(1);
LinearSystem<N2, N1, N2> plant = LinearSystemId.createDCMotorSystem(gearbox, 0.0005, 1);
LinearSystem<N2, N1, N2> plant =
Models.singleJointedArmFromPhysicalConstants(gearbox, 0.0005, 1);
DCMotorSim sim = new DCMotorSim(plant, gearbox);
try (var motor = new PWMVictorSPX(0);
@@ -64,7 +65,8 @@ class DCMotorSimTest {
RoboRioSim.resetData();
DCMotor gearbox = DCMotor.getNEO(1);
LinearSystem<N2, N1, N2> plant = LinearSystemId.createDCMotorSystem(gearbox, 0.0005, 1);
LinearSystem<N2, N1, N2> plant =
Models.singleJointedArmFromPhysicalConstants(gearbox, 0.0005, 1);
DCMotorSim sim = new DCMotorSim(plant, gearbox);
try (var motor = new PWMVictorSPX(0);

View File

@@ -19,9 +19,9 @@ import org.wpilib.math.linalg.VecBuilder;
import org.wpilib.math.linalg.Vector;
import org.wpilib.math.numbers.N1;
import org.wpilib.math.numbers.N7;
import org.wpilib.math.system.DCMotor;
import org.wpilib.math.system.Models;
import org.wpilib.math.system.NumericalIntegration;
import org.wpilib.math.system.plant.DCMotor;
import org.wpilib.math.system.plant.LinearSystemId;
import org.wpilib.math.trajectory.TrajectoryConfig;
import org.wpilib.math.trajectory.TrajectoryGenerator;
import org.wpilib.math.trajectory.constraint.DifferentialDriveKinematicsConstraint;
@@ -33,7 +33,7 @@ class DifferentialDrivetrainSimTest {
void testConvergence() {
var motor = DCMotor.getNEO(2);
var plant =
LinearSystemId.createDrivetrainVelocitySystem(
Models.differentialDriveFromPhysicalConstants(
motor, 50, Units.inchesToMeters(2), Units.inchesToMeters(12), 0.5, 1.0);
var kinematics = new DifferentialDriveKinematics(Units.inchesToMeters(24));
@@ -97,7 +97,7 @@ class DifferentialDrivetrainSimTest {
void testCurrent() {
var motor = DCMotor.getNEO(2);
var plant =
LinearSystemId.createDrivetrainVelocitySystem(
Models.differentialDriveFromPhysicalConstants(
motor, 50, Units.inchesToMeters(2), Units.inchesToMeters(12), 0.5, 1.0);
var kinematics = new DifferentialDriveKinematics(Units.inchesToMeters(24));
var sim =
@@ -127,7 +127,7 @@ class DifferentialDrivetrainSimTest {
void testModelStability() {
var motor = DCMotor.getNEO(2);
var plant =
LinearSystemId.createDrivetrainVelocitySystem(
Models.differentialDriveFromPhysicalConstants(
motor, 50, Units.inchesToMeters(2), Units.inchesToMeters(12), 2.0, 5.0);
var kinematics = new DifferentialDriveKinematics(Units.inchesToMeters(24));

View File

@@ -12,8 +12,8 @@ import org.wpilib.hardware.motor.PWMVictorSPX;
import org.wpilib.hardware.rotation.Encoder;
import org.wpilib.math.controller.PIDController;
import org.wpilib.math.linalg.VecBuilder;
import org.wpilib.math.system.plant.DCMotor;
import org.wpilib.math.system.plant.LinearSystemId;
import org.wpilib.math.system.DCMotor;
import org.wpilib.math.system.Models;
import org.wpilib.math.util.Units;
import org.wpilib.system.RobotController;
@@ -117,7 +117,7 @@ class ElevatorSimTest {
}
var system =
LinearSystemId.createElevatorSystem(
Models.elevatorFromPhysicalConstants(
DCMotor.getVex775Pro(4), 4, Units.inchesToMeters(0.5), 100);
assertEquals(
system.calculateX(VecBuilder.fill(0, 0), VecBuilder.fill(12), 0.02 * 50.0).get(0, 0),

View File

@@ -8,7 +8,7 @@ import static org.junit.jupiter.api.Assertions.assertEquals;
import org.junit.jupiter.api.Test;
import org.wpilib.math.linalg.VecBuilder;
import org.wpilib.math.system.plant.DCMotor;
import org.wpilib.math.system.DCMotor;
import org.wpilib.math.util.Units;
class SingleJointedArmSimTest {