mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
[wpimath] LinearSystemId: Fix docs, move C++ impls out of header (#4388)
- Fix inaccuracies and inconsistencies in Java & C++ LinearSystemId documentation. - Move LinearSystemId function definitions to LinearSystemId.cpp
This commit is contained in:
@@ -20,9 +20,9 @@ public final class LinearSystemId {
|
||||
* Create a state-space model of an elevator system. The states of the system are [position,
|
||||
* velocity]ᵀ, inputs are [voltage], and outputs are [position].
|
||||
*
|
||||
* @param motor The motor (or gearbox) attached to the arm.
|
||||
* @param motor The motor (or gearbox) attached to the carriage.
|
||||
* @param massKg The mass of the elevator carriage, in kilograms.
|
||||
* @param radiusMeters The radius of thd driving drum of the elevator, in meters.
|
||||
* @param radiusMeters The radius of the elevator's driving drum, in meters.
|
||||
* @param G The reduction between motor and drum, as a ratio of output to input.
|
||||
* @return A LinearSystem representing the given characterized constants.
|
||||
* @throws IllegalArgumentException if massKg <= 0, radiusMeters <= 0, or G <= 0.
|
||||
@@ -63,15 +63,15 @@ public final class LinearSystemId {
|
||||
* velocity], inputs are [voltage], and outputs are [angular velocity].
|
||||
*
|
||||
* @param motor The motor (or gearbox) attached to the flywheel.
|
||||
* @param jKgMetersSquared The moment of inertia J of the flywheel.
|
||||
* @param JKgMetersSquared The moment of inertia J of the flywheel.
|
||||
* @param G The reduction between motor and drum, as a ratio of output to input.
|
||||
* @return A LinearSystem representing the given characterized constants.
|
||||
* @throws IllegalArgumentException if jKgMetersSquared <= 0 or G <= 0.
|
||||
* @throws IllegalArgumentException if JKgMetersSquared <= 0 or G <= 0.
|
||||
*/
|
||||
@SuppressWarnings("ParameterName")
|
||||
public static LinearSystem<N1, N1, N1> createFlywheelSystem(
|
||||
DCMotor motor, double jKgMetersSquared, double G) {
|
||||
if (jKgMetersSquared <= 0.0) {
|
||||
DCMotor motor, double JKgMetersSquared, double G) {
|
||||
if (JKgMetersSquared <= 0.0) {
|
||||
throw new IllegalArgumentException("J must be greater than zero.");
|
||||
}
|
||||
if (G <= 0.0) {
|
||||
@@ -83,8 +83,8 @@ public final class LinearSystemId {
|
||||
-G
|
||||
* G
|
||||
* motor.KtNMPerAmp
|
||||
/ (motor.KvRadPerSecPerVolt * motor.rOhms * jKgMetersSquared)),
|
||||
VecBuilder.fill(G * motor.KtNMPerAmp / (motor.rOhms * jKgMetersSquared)),
|
||||
/ (motor.KvRadPerSecPerVolt * motor.rOhms * JKgMetersSquared)),
|
||||
VecBuilder.fill(G * motor.KtNMPerAmp / (motor.rOhms * JKgMetersSquared)),
|
||||
Matrix.eye(Nat.N1()),
|
||||
new Matrix<>(Nat.N1(), Nat.N1()));
|
||||
}
|
||||
@@ -94,16 +94,16 @@ public final class LinearSystemId {
|
||||
* position, angular velocity], inputs are [voltage], and outputs are [angular position, angular
|
||||
* velocity].
|
||||
*
|
||||
* @param motor The motor (or gearbox) attached to the DC motor.
|
||||
* @param jKgMetersSquared The moment of inertia J of the DC motor.
|
||||
* @param motor The motor (or gearbox) attached to system.
|
||||
* @param JKgMetersSquared The moment of inertia J of the DC motor.
|
||||
* @param G The reduction between motor and drum, as a ratio of output to input.
|
||||
* @return A LinearSystem representing the given characterized constants.
|
||||
* @throws IllegalArgumentException if jKgMetersSquared <= 0 or G <= 0.
|
||||
* @throws IllegalArgumentException if JKgMetersSquared <= 0 or G <= 0.
|
||||
*/
|
||||
@SuppressWarnings("ParameterName")
|
||||
public static LinearSystem<N2, N1, N2> createDCMotorSystem(
|
||||
DCMotor motor, double jKgMetersSquared, double G) {
|
||||
if (jKgMetersSquared <= 0.0) {
|
||||
DCMotor motor, double JKgMetersSquared, double G) {
|
||||
if (JKgMetersSquared <= 0.0) {
|
||||
throw new IllegalArgumentException("J must be greater than zero.");
|
||||
}
|
||||
if (G <= 0.0) {
|
||||
@@ -119,22 +119,23 @@ public final class LinearSystemId {
|
||||
-G
|
||||
* G
|
||||
* motor.KtNMPerAmp
|
||||
/ (motor.KvRadPerSecPerVolt * motor.rOhms * jKgMetersSquared)),
|
||||
VecBuilder.fill(0, G * motor.KtNMPerAmp / (motor.rOhms * jKgMetersSquared)),
|
||||
/ (motor.KvRadPerSecPerVolt * motor.rOhms * JKgMetersSquared)),
|
||||
VecBuilder.fill(0, G * motor.KtNMPerAmp / (motor.rOhms * JKgMetersSquared)),
|
||||
Matrix.eye(Nat.N2()),
|
||||
new Matrix<>(Nat.N2(), Nat.N1()));
|
||||
}
|
||||
|
||||
/**
|
||||
* Create a state-space model of a differential drive drivetrain. In this model, the states are
|
||||
* [v_left, v_right]ᵀ, inputs are [V_left, V_right]ᵀ and outputs are [v_left, v_right]ᵀ.
|
||||
* [left velocity, right velocity]ᵀ, inputs are [left voltage, right voltage]ᵀ, and outputs are
|
||||
* [left velocity, right velocity]ᵀ.
|
||||
*
|
||||
* @param motor the gearbox representing the motors driving the drivetrain.
|
||||
* @param massKg the mass of the robot.
|
||||
* @param rMeters the radius of the wheels in meters.
|
||||
* @param rbMeters the radius of the base (half the track width) in meters.
|
||||
* @param JKgMetersSquared the moment of inertia of the robot.
|
||||
* @param G the gearing reduction as output over input.
|
||||
* @param motor The motor (or gearbox) driving the drivetrain.
|
||||
* @param massKg The mass of the robot in kilograms.
|
||||
* @param rMeters The radius of the wheels in meters.
|
||||
* @param rbMeters The radius of the base (half the track width) in meters.
|
||||
* @param JKgMetersSquared The moment of inertia of the robot.
|
||||
* @param G The gearing reduction as output over input.
|
||||
* @return A LinearSystem representing a differential drivetrain.
|
||||
* @throws IllegalArgumentException if m <= 0, r <= 0, rb <= 0, J <= 0, or G <= 0.
|
||||
*/
|
||||
@@ -181,16 +182,16 @@ public final class LinearSystemId {
|
||||
* angular velocity], inputs are [voltage], and outputs are [angle].
|
||||
*
|
||||
* @param motor The motor (or gearbox) attached to the arm.
|
||||
* @param jKgSquaredMeters The moment of inertia J of the arm.
|
||||
* @param JKgSquaredMeters The moment of inertia J of the arm.
|
||||
* @param G The gearing between the motor and arm, in output over input. Most of the time this
|
||||
* will be greater than 1.
|
||||
* @return A LinearSystem representing the given characterized constants.
|
||||
*/
|
||||
@SuppressWarnings("ParameterName")
|
||||
public static LinearSystem<N2, N1, N1> createSingleJointedArmSystem(
|
||||
DCMotor motor, double jKgSquaredMeters, double G) {
|
||||
if (jKgSquaredMeters <= 0.0) {
|
||||
throw new IllegalArgumentException("jKgSquaredMeters must be greater than zero.");
|
||||
DCMotor motor, double JKgSquaredMeters, double G) {
|
||||
if (JKgSquaredMeters <= 0.0) {
|
||||
throw new IllegalArgumentException("JKgSquaredMeters must be greater than zero.");
|
||||
}
|
||||
if (G <= 0.0) {
|
||||
throw new IllegalArgumentException("G must be greater than zero.");
|
||||
@@ -204,22 +205,26 @@ public final class LinearSystemId {
|
||||
0,
|
||||
-Math.pow(G, 2)
|
||||
* motor.KtNMPerAmp
|
||||
/ (motor.KvRadPerSecPerVolt * motor.rOhms * jKgSquaredMeters)),
|
||||
VecBuilder.fill(0, G * motor.KtNMPerAmp / (motor.rOhms * jKgSquaredMeters)),
|
||||
/ (motor.KvRadPerSecPerVolt * motor.rOhms * JKgSquaredMeters)),
|
||||
VecBuilder.fill(0, G * motor.KtNMPerAmp / (motor.rOhms * JKgSquaredMeters)),
|
||||
Matrix.mat(Nat.N1(), Nat.N2()).fill(1, 0),
|
||||
new Matrix<>(Nat.N1(), Nat.N1()));
|
||||
}
|
||||
|
||||
/**
|
||||
* Identify a velocity system from it's kV (volts/(unit/sec)) and kA (volts/(unit/sec²). These
|
||||
* constants cam be found using SysId. The states of the system are [velocity], inputs are
|
||||
* [voltage], and outputs are [velocity].
|
||||
* Create a state-space model for a 1 DOF velocity system from its kV (volts/(unit/sec)) and kA
|
||||
* (volts/(unit/sec²). These constants cam be found using SysId. The states of the system are
|
||||
* [velocity], inputs are [voltage], and outputs are [velocity].
|
||||
*
|
||||
* <p>The distance unit you choose MUST be an SI unit (i.e. meters or radians). You can use the
|
||||
* {@link edu.wpi.first.math.util.Units} class for converting between unit types.
|
||||
*
|
||||
* @param kV The velocity gain, in volts per (units per second)
|
||||
* @param kA The acceleration gain, in volts per (units per second squared)
|
||||
* <p>The parameters provided by the user are from this feedforward model:
|
||||
*
|
||||
* <p>u = K_v v + K_a a
|
||||
*
|
||||
* @param kV The velocity gain, in volts/(unit/sec)
|
||||
* @param kA The acceleration gain, in volts/(unit/sec^2)
|
||||
* @return A LinearSystem representing the given characterized constants.
|
||||
* @throws IllegalArgumentException if kV <= 0 or kA <= 0.
|
||||
* @see <a href="https://github.com/wpilibsuite/sysid">https://github.com/wpilibsuite/sysid</a>
|
||||
@@ -241,15 +246,19 @@ public final class LinearSystemId {
|
||||
}
|
||||
|
||||
/**
|
||||
* Identify a position system from it's kV (volts/(unit/sec)) and kA (volts/(unit/sec²). These
|
||||
* constants cam be found using SysId. The states of the system are [position, velocity]ᵀ, inputs
|
||||
* are [voltage], and outputs are [position].
|
||||
* Create a state-space model for a 1 DOF position system from its kV (volts/(unit/sec)) and kA
|
||||
* (volts/(unit/sec²). These constants cam be found using SysId. The states of the system are
|
||||
* [position, velocity]ᵀ, inputs are [voltage], and outputs are [position].
|
||||
*
|
||||
* <p>The distance unit you choose MUST be an SI unit (i.e. meters or radians). You can use the
|
||||
* {@link edu.wpi.first.math.util.Units} class for converting between unit types.
|
||||
*
|
||||
* @param kV The velocity gain, in volts per (units per second)
|
||||
* @param kA The acceleration gain, in volts per (units per second squared)
|
||||
* <p>The parameters provided by the user are from this feedforward model:
|
||||
*
|
||||
* <p>u = K_v v + K_a a
|
||||
*
|
||||
* @param kV The velocity gain, in volts/(unit/sec)
|
||||
* @param kA The acceleration gain, in volts/(unit/sec²)
|
||||
* @return A LinearSystem representing the given characterized constants.
|
||||
* @throws IllegalArgumentException if kV <= 0 or kA <= 0.
|
||||
* @see <a href="https://github.com/wpilibsuite/sysid">https://github.com/wpilibsuite/sysid</a>
|
||||
@@ -272,17 +281,17 @@ public final class LinearSystemId {
|
||||
|
||||
/**
|
||||
* Identify a differential drive drivetrain given the drivetrain's kV and kA in both linear
|
||||
* (volts/(meter/sec) and volts/(meter/sec²)) and angular (volts/(radian/sec) and
|
||||
* volts/(radian/sec²)) cases. This can be found using SysId.
|
||||
* {(volts/(meter/sec), (volts/(meter/sec²))} and angular {(volts/(radian/sec)),
|
||||
* (volts/(radian/sec²))} cases. These constants can be found using SysId.
|
||||
*
|
||||
* <p>States: [[left velocity], [right velocity]]<br>
|
||||
* Inputs: [[left voltage], [right voltage]]<br>
|
||||
* Outputs: [[left velocity], [right velocity]]
|
||||
*
|
||||
* @param kVLinear The linear velocity gain, volts per (meter per second).
|
||||
* @param kALinear The linear acceleration gain, volts per (meter per second squared).
|
||||
* @param kVAngular The angular velocity gain, volts per (meter per second).
|
||||
* @param kAAngular The angular acceleration gain, volts per (meter per second squared).
|
||||
* @param kVLinear The linear velocity gain in volts per (meters per second).
|
||||
* @param kALinear The linear acceleration gain in volts per (meters per second squared).
|
||||
* @param kVAngular The angular velocity gain in volts per (radians per second).
|
||||
* @param kAAngular The angular acceleration gain in volts per (radians per second squared).
|
||||
* @return A LinearSystem representing the given characterized constants.
|
||||
* @throws IllegalArgumentException if kVLinear <= 0, kALinear <= 0, kVAngular <= 0, or
|
||||
* kAAngular <= 0.
|
||||
@@ -318,18 +327,18 @@ public final class LinearSystemId {
|
||||
|
||||
/**
|
||||
* Identify a differential drive drivetrain given the drivetrain's kV and kA in both linear
|
||||
* (volts/(meter/sec) and volts/(meter/sec²)) and angular (volts/(radian/sec) and
|
||||
* volts/(radian/sec²)) cases. This can be found using SysId.
|
||||
* {(volts/(meter/sec)), (volts/(meter/sec²))} and angular {(volts/(radian/sec)),
|
||||
* (volts/(radian/sec²))} cases. This can be found using SysId.
|
||||
*
|
||||
* <p>States: [[left velocity], [right velocity]]<br>
|
||||
* Inputs: [[left voltage], [right voltage]]<br>
|
||||
* Outputs: [[left velocity], [right velocity]]
|
||||
*
|
||||
* @param kVLinear The linear velocity gain, volts per (meter per second).
|
||||
* @param kALinear The linear acceleration gain, volts per (meter per second squared).
|
||||
* @param kVAngular The angular velocity gain, volts per (radians per second).
|
||||
* @param kAAngular The angular acceleration gain, volts per (radians per second squared).
|
||||
* @param trackwidth The distance between the differential drive's left and right wheels in
|
||||
* @param kVLinear The linear velocity gain in volts per (meters per second).
|
||||
* @param kALinear The linear acceleration gain in volts per (meters per second squared).
|
||||
* @param kVAngular The angular velocity gain in volts per (radians per second).
|
||||
* @param kAAngular The angular acceleration gain in volts per (radians per second squared).
|
||||
* @param trackwidth The distance between the differential drive's left and right wheels, in
|
||||
* meters.
|
||||
* @return A LinearSystem representing the given characterized constants.
|
||||
* @throws IllegalArgumentException if kVLinear <= 0, kALinear <= 0, kVAngular <= 0,
|
||||
|
||||
Reference in New Issue
Block a user