Package yams.math
Class LQRConfig
java.lang.Object
yams.math.LQRConfig
LQR Configuration for
LQRController-
Nested Class Summary
Nested Classes -
Constructor Summary
ConstructorsConstructorDescriptionLQRConfig(DCMotor motor, MechanismGearing gearing, MomentOfInertia moi) Create a new LQR Configuration. -
Method Summary
Modifier and TypeMethodDescriptionKalmanFilter<?,?, ?> getKalmanFilter(LinearSystem<?, ?, ?> plant) Get theKalmanFilterfor the LQR.LinearSystemLoop<?,?, ?> getLoop()Get theLinearSystemLoopwith the currently configured LQR.LinearSystemLoop<?,?, ?> getLoop(LinearSystem<?, ?, ?> plant, LinearQuadraticRegulator<?, ?, ?> controller, KalmanFilter<?, ?, ?> observer) Get theLinearSystemLoop.Get the loop time for the LQR.LinearQuadraticRegulator<?,?, ?> getRegulator(LinearSystem<?, ?, ?> plant) Get theLinearQuadraticRegulator.LinearSystem<?,?, ?> Get theLinearSystemfor the LQR.getType()Get theLQRConfig.LQRTypeof the LQR.withAgressiveness(double agressiveness) Agressiveness of the LQR, howfast it will attempt to achieve the desired state.withArm(Angle qelmsPosition, AngularVelocity qelmsVelocity, Angle modelPositionTrust, AngularVelocity modelVelocityTrust, Angle encoderPositionTrust) Construct an Arm LQR Configuration.withControlEffort(Voltage effort) Set the control effort for the LQR.withElevator(Distance qelmsPosition, LinearVelocity qelmsVelocity, Distance modelPositionTrust, LinearVelocity modelVelocityTrust, Distance encoderPositionTrust, Mass mass, Distance drumRadius) Construct an Elevator LQR Configuration.withFlyWheel(AngularVelocity qelms, AngularVelocity modelTrust, AngularVelocity encoderTrust) Construct a Flywheel LQR Configuration.withMaxVoltage(Voltage voltage) Set the maximum voltage for theLinearSystemLoop.withMeasurementDelay(Time delay) Set the measurement delay of the LQR.Set the control effort for the LQR.
-
Constructor Details
-
LQRConfig
Create a new LQR Configuration.- Parameters:
motor-DCMotorfor theLinearQuadraticRegulator.gearing-MechanismGearingfor theLinearQuadraticRegulator.moi-MomentOfInertiafor theLinearQuadraticRegulator.
-
-
Method Details
-
getType
Get theLQRConfig.LQRTypeof the LQR.- Returns:
LQRConfig.LQRTypeof the LQR.
-
getPeriod
Get the loop time for the LQR.- Returns:
Timefor the loop time.
-
withRelms
Set the control effort for the LQR.- Parameters:
relms- Control effort (voltage) tolerance. Decrease this to more heavily penalize control effort, or make the controller less aggressive. 12 is a good starting point because that is the (approximate) maximum voltage of a battery.- Returns:
LQRConfigfor chaining.
-
withControlEffort
Set the control effort for the LQR.- Parameters:
effort- Control effort (voltage) tolerance. Decrease this to more heavily penalize control effort, or make the controller less aggressive. 12 is a good starting point because that is the (approximate) maximum voltage of a battery.- Returns:
LQRConfigfor chaining.
-
withMaxVoltage
Set the maximum voltage for theLinearSystemLoop.- Parameters:
voltage- Maximum voltage output.- Returns:
LQRConfigfor chaining.
-
withMeasurementDelay
Set the measurement delay of the LQR.- Parameters:
delay- Measurement delay.- Returns:
LQRConfigfor chaining.
-
withAgressiveness
Agressiveness of the LQR, howfast it will attempt to achieve the desired state.- Parameters:
agressiveness- Usually 10, arbitrary scale.- Returns:
LQRConfigfor chaining.
-
withFlyWheel
public LQRConfig withFlyWheel(AngularVelocity qelms, AngularVelocity modelTrust, AngularVelocity encoderTrust) Construct a Flywheel LQR Configuration.- Parameters:
qelms- Velocity error tolerance. Decrease this to more heavily penalize state excursion, or make the controller behave more starting point because that is the (approximate) maximum voltage of a battery.modelTrust- Standard deviation of the model, represented inAngularVelocity.encoderTrust- Standard deviation of the encoder, represented inAngularVelocity.- Returns:
LQRConfigfor chaining.
-
withElevator
public LQRConfig withElevator(Distance qelmsPosition, LinearVelocity qelmsVelocity, Distance modelPositionTrust, LinearVelocity modelVelocityTrust, Distance encoderPositionTrust, Mass mass, Distance drumRadius) Construct an Elevator LQR Configuration.- Parameters:
qelmsPosition- Position error tolerance, in meters. Decrease this to more heavily penalize state excursion, or make the controller behave more aggressively. This can be tuned to balance the position and velocity errors.qelmsVelocity- Velocity error tolerance, in meters per second. Decrease this to more heavily penalize state excursion, or make the controller behave more aggressively. This can be tuned to balance the position and velocity errors.modelPositionTrust- Standard deviation of the model position, represented inDistance.modelVelocityTrust- Standard deviation of the model velocity, represented inLinearVelocity.encoderPositionTrust- Standard deviation of the encoder position, represented inDistance.mass- Mass of the elevator, represented inMass.drumRadius- Radius of the elevator drum, represented inDistance.- Returns:
LQRConfigfor chaining.
-
withArm
public LQRConfig withArm(Angle qelmsPosition, AngularVelocity qelmsVelocity, Angle modelPositionTrust, AngularVelocity modelVelocityTrust, Angle encoderPositionTrust) Construct an Arm LQR Configuration.- Parameters:
qelmsPosition- Position error tolerance, in rotations. Decrease this to more heavily penalize state excursion, or make the controller behave more aggressively. This can be tuned to balance the position and velocity errors.qelmsVelocity- Velocity error tolerance, in rotations per second. Decrease this to more heavily penalize state excursion, or make the controller behave more aggressively. This can be tuned to balance the position and velocity errors.modelPositionTrust- Standard deviation of the model position, represented inAngle.modelVelocityTrust- Standard deviation of the model velocity, represented inAngularVelocity.encoderPositionTrust- Standard deviation of the encoder position, represented inAngle.- Returns:
LQRConfigfor chaining.
-
getSystem
Get theLinearSystemfor the LQR. withLinearSystemId- Returns:
LinearSystemfor the LQR.
-
getKalmanFilter
Get theKalmanFilterfor the LQR.- Parameters:
plant-LinearSystemfor the LQR, fetched fromgetSystem().- Returns:
KalmanFilterfor the LQR.
-
getRegulator
Get theLinearQuadraticRegulator.- Parameters:
plant-LinearSystemfor the LQR, fetched fromgetSystem().- Returns:
LinearQuadraticRegulatorfor the LQR.
-
getLoop
public LinearSystemLoop<?,?, getLoop?> (LinearSystem<?, ?, ?> plant, LinearQuadraticRegulator<?, ?, ?> controller, KalmanFilter<?, ?, ?> observer) Get theLinearSystemLoop.- Parameters:
plant-LinearSystemfor the LQR, fetched fromgetSystem()controller-LinearQuadraticRegulatorfor the LQR, fetched fromgetRegulator(LinearSystem)observer-KalmanFilterfor the LQR, fetched fromgetKalmanFilter(LinearSystem)- Returns:
LinearSystemLoopfor the LQR.
-
getLoop
Get theLinearSystemLoopwith the currently configured LQR.- Returns:
LinearSystemLoopfor the LQR.
-