[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 @@ package org.wpilib.simulation;
import org.wpilib.math.linalg.VecBuilder;
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.system.RobotController;
/** Represents a simulated DC motor mechanism. */
@@ -26,10 +26,9 @@ public class DCMotorSim extends LinearSystemSim<N2, N1, N2> {
* Creates a simulated DC motor mechanism.
*
* @param plant The linear system representing the DC motor. This system can be created with
* {@link org.wpilib.math.system.plant.LinearSystemId#createDCMotorSystem(DCMotor, double,
* double)} or {@link org.wpilib.math.system.plant.LinearSystemId#createDCMotorSystem(double,
* double)}. If {@link org.wpilib.math.system.plant.LinearSystemId#createDCMotorSystem(double,
* double)} is used, the distance unit must be radians.
* {@link org.wpilib.math.system.Models#singleJointedArmFromPhysicalConstants(DCMotor, double,
* double)} or {@link org.wpilib.math.system.Models#singleJointedArmFromSysId(double,
* double)}.
* @param gearbox The type of and number of motors in the DC motor gearbox.
* @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no
* noise is desired. If present must have 2 elements. The first element is for position. The

View File

@@ -12,10 +12,10 @@ import org.wpilib.math.numbers.N1;
import org.wpilib.math.numbers.N2;
import org.wpilib.math.numbers.N7;
import org.wpilib.math.random.Normal;
import org.wpilib.math.system.DCMotor;
import org.wpilib.math.system.LinearSystem;
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.util.Nat;
import org.wpilib.math.util.StateSpaceUtil;
import org.wpilib.math.util.Units;
@@ -77,7 +77,7 @@ public class DifferentialDrivetrainSim {
double trackwidth,
Matrix<N7, N1> measurementStdDevs) {
this(
LinearSystemId.createDrivetrainVelocitySystem(
Models.differentialDriveFromPhysicalConstants(
driveMotor, mass, wheelRadius, trackwidth / 2.0, j, gearing),
driveMotor,
gearing,
@@ -91,10 +91,9 @@ public class DifferentialDrivetrainSim {
*
* @param plant The {@link LinearSystem} representing the robot's drivetrain. This system can be
* created with {@link
* org.wpilib.math.system.plant.LinearSystemId#createDrivetrainVelocitySystem(DCMotor, double,
* org.wpilib.math.system.Models#differentialDriveFromPhysicalConstants(DCMotor, double,
* double, double, double, double)} or {@link
* org.wpilib.math.system.plant.LinearSystemId#identifyDrivetrainSystem(double, double,
* double, double)}.
* org.wpilib.math.system.Models#differentialDriveFromSysId(double, double, double, double)}.
* @param driveMotor A {@link DCMotor} representing the drivetrain.
* @param gearing The gearingRatio ratio of the robot, as output over input. This must be the same
* ratio as the ratio used to identify or create the drivetrainPlant.

View File

@@ -8,10 +8,10 @@ import org.wpilib.math.linalg.Matrix;
import org.wpilib.math.linalg.VecBuilder;
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.Models;
import org.wpilib.math.system.NumericalIntegration;
import org.wpilib.math.system.plant.DCMotor;
import org.wpilib.math.system.plant.LinearSystemId;
import org.wpilib.system.RobotController;
/** Represents a simulated elevator mechanism. */
@@ -32,8 +32,8 @@ public class ElevatorSim extends LinearSystemSim<N2, N1, N2> {
* Creates a simulated elevator mechanism.
*
* @param plant The linear system that represents the elevator. This system can be created with
* {@link org.wpilib.math.system.plant.LinearSystemId#createElevatorSystem(DCMotor, double,
* double, double)}.
* {@link org.wpilib.math.system.Models#elevatorFromPhysicalConstants(DCMotor, double, double,
* double)}.
* @param gearbox The type of and number of motors in the elevator gearbox.
* @param minHeight The min allowable height of the elevator in meters.
* @param maxHeight The max allowable height of the elevator in meters.
@@ -83,7 +83,7 @@ public class ElevatorSim extends LinearSystemSim<N2, N1, N2> {
double startingHeight,
double... measurementStdDevs) {
this(
LinearSystemId.identifyPositionSystem(kV, kA),
Models.elevatorFromSysId(kV, kA),
gearbox,
minHeight,
maxHeight,
@@ -117,7 +117,7 @@ public class ElevatorSim extends LinearSystemSim<N2, N1, N2> {
double startingHeight,
double... measurementStdDevs) {
this(
LinearSystemId.createElevatorSystem(gearbox, carriageMass, drumRadius, gearing),
Models.elevatorFromPhysicalConstants(gearbox, carriageMass, drumRadius, gearing),
gearbox,
minHeight,
maxHeight,

View File

@@ -6,9 +6,9 @@ package org.wpilib.simulation;
import org.wpilib.math.linalg.VecBuilder;
import org.wpilib.math.numbers.N1;
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;
/** Represents a simulated flywheel mechanism. */
@@ -26,9 +26,8 @@ public class FlywheelSim extends LinearSystemSim<N1, N1, N1> {
* Creates a simulated flywheel mechanism.
*
* @param plant The linear system that represents the flywheel. Use either {@link
* LinearSystemId#createFlywheelSystem(DCMotor, double, double)} if using physical constants
* or {@link LinearSystemId#identifyVelocitySystem(double, double)} if using system
* characterization.
* Models#flywheelFromPhysicalConstants(DCMotor, double, double)} if using physical constants
* or {@link Models#flywheelFromSysId(double, double)} if using system characterization.
* @param gearbox The type of and number of motors in the flywheel gearbox.
* @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no
* noise is desired. If present must have 1 element for velocity.

View File

@@ -8,10 +8,10 @@ import org.wpilib.math.linalg.Matrix;
import org.wpilib.math.linalg.VecBuilder;
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.Models;
import org.wpilib.math.system.NumericalIntegration;
import org.wpilib.math.system.plant.DCMotor;
import org.wpilib.math.system.plant.LinearSystemId;
import org.wpilib.system.RobotController;
/** Represents a simulated single jointed arm mechanism. */
@@ -38,7 +38,7 @@ public class SingleJointedArmSim extends LinearSystemSim<N2, N1, N2> {
* Creates a simulated arm mechanism.
*
* @param plant The linear system that represents the arm. This system can be created with {@link
* org.wpilib.math.system.plant.LinearSystemId#createSingleJointedArmSystem(DCMotor, double,
* org.wpilib.math.system.Models#singleJointedArmFromPhysicalConstants(DCMotor, double,
* double)}.
* @param gearbox The type of and number of motors in the arm gearbox.
* @param gearing The gearing of the arm (numbers greater than 1 represent reductions).
@@ -97,7 +97,7 @@ public class SingleJointedArmSim extends LinearSystemSim<N2, N1, N2> {
double startingAngleRads,
double... measurementStdDevs) {
this(
LinearSystemId.createSingleJointedArmSystem(gearbox, j, gearing),
Models.singleJointedArmFromPhysicalConstants(gearbox, j, gearing),
gearbox,
gearing,
armLength,