Class Slot0Configs
- All Implemented Interfaces:
ParentConfiguration,ISerializable,Cloneable
If this slot is selected, these gains are used in closed loop control requests.
-
Field Summary
FieldsModifier and TypeFieldDescriptionThe behavior of the gain scheduler on this slot.doubleGravity feedback position offset when using the Arm/Cosine gravity type.Gravity feedforward/feedback type.doubleAcceleration feedforward gain.doubleDerivative gain.doubleGravity feedforward/feedback gain.doubleIntegral gain.doubleProportional gain.doubleStatic feedforward gain.doubleVelocity feedforward gain.Static feedforward sign during position closed loop. -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionclone()final StatusCodedeserialize(String to_deserialize) Take a string and deserialize it to this configuration group.static Slot0Configsfrom(SlotConfigs value) Converts the provided value to an instance of this type.final AngleHelper method to get this configuration's GravityArmPositionOffset parameter converted to a unit type.final StringGet the serialized form of this configuration group.toString()final Slot0ConfigswithGainSchedBehavior(GainSchedBehaviorValue newGainSchedBehavior) Modifies this configuration's GainSchedBehavior parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithGravityArmPositionOffset(double newGravityArmPositionOffset) Modifies this configuration's GravityArmPositionOffset parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithGravityArmPositionOffset(Angle newGravityArmPositionOffset) Modifies this configuration's GravityArmPositionOffset parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithGravityType(GravityTypeValue newGravityType) Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithKA(double newKA) Modifies this configuration's kA parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithKD(double newKD) Modifies this configuration's kD parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithKG(double newKG) Modifies this configuration's kG parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithKI(double newKI) Modifies this configuration's kI parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithKP(double newKP) Modifies this configuration's kP parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithKS(double newKS) Modifies this configuration's kS parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithKV(double newKV) Modifies this configuration's kV parameter and returns itself for method-chaining and easier to use config API.final Slot0ConfigswithStaticFeedforwardSign(StaticFeedforwardSignValue newStaticFeedforwardSign) Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining and easier to use config API.
-
Field Details
-
kP
Proportional gain.The units for this gain is dependent on the control mode. Since this gain is multiplied by error in the input, the units should be defined as units of output per unit of input error. For example, when controlling velocity using a duty cycle closed loop, the units for the proportional gain will be duty cycle per rps of error, or 1/rps.
- Minimum Value: 0
- Maximum Value: 3.4e+38
- Default Value: 0
- Units:
-
kI
Integral gain.The units for this gain is dependent on the control mode. Since this gain is multiplied by error in the input integrated over time (in units of seconds), the units should be defined as units of output per unit of integrated input error. For example, when controlling velocity using a duty cycle closed loop, integrating velocity over time results in rps * s = rotations. Therefore, the units for the integral gain will be duty cycle per rotation of accumulated error, or 1/rot.
- Minimum Value: 0
- Maximum Value: 3.4e+38
- Default Value: 0
- Units:
-
kD
Derivative gain.The units for this gain is dependent on the control mode. Since this gain is multiplied by the derivative of error in the input with respect to time (in units of seconds), the units should be defined as units of output per unit of the differentiated input error. For example, when controlling velocity using a duty cycle closed loop, the derivative of velocity with respect to time is rot per sec², which is acceleration. Therefore, the units for the derivative gain will be duty cycle per unit of acceleration error, or 1/(rot per sec²).
- Minimum Value: 0
- Maximum Value: 3.4e+38
- Default Value: 0
- Units:
-
kS
Static feedforward gain.This is added to the closed loop output. The unit for this constant is dependent on the control mode, typically fractional duty cycle, voltage, or torque current.
The sign is typically determined by reference velocity when using position, velocity, and Motion Magic® closed loop modes. However, when using position closed loop with zero velocity reference (no motion profiling), the application can instead use the position closed loop error by setting the Static Feedforward Sign configuration parameter. When doing so, we recommend the minimal amount of kS, otherwise the motor output may dither when closed loop error is near zero.
- Minimum Value: -128
- Maximum Value: 127
- Default Value: 0
- Units:
-
kV
Velocity feedforward gain.The units for this gain is dependent on the control mode. Since this gain is multiplied by the requested velocity, the units should be defined as units of output per unit of requested input velocity. For example, when controlling velocity using a duty cycle closed loop, the units for the velocity feedfoward gain will be duty cycle per requested rps, or 1/rps.
- Minimum Value: 0
- Maximum Value: 3.4e+38
- Default Value: 0
- Units:
-
kA
Acceleration feedforward gain.The units for this gain is dependent on the control mode. Since this gain is multiplied by the requested acceleration, the units should be defined as units of output per unit of requested input acceleration. For example, when controlling velocity using a duty cycle closed loop, the units for the acceleration feedfoward gain will be duty cycle per requested rot per sec², or 1/(rot per sec²).
- Minimum Value: 0
- Maximum Value: 3.4e+38
- Default Value: 0
- Units:
-
kG
Gravity feedforward/feedback gain. The type of gravity compensation is selected byGravityType.This is added to the closed loop output. The sign is determined by the gravity type. The unit for this constant is dependent on the control mode, typically fractional duty cycle, voltage, or torque current.
- Minimum Value: -128
- Maximum Value: 127
- Default Value: 0
- Units:
-
GravityType
Gravity feedforward/feedback type.This determines the type of the gravity feedforward/feedback.
Choose Elevator_Static for systems where the gravity feedforward is constant, such as an elevator. The gravity feedforward output will always have the same sign.
Choose Arm_Cosine for systems where the gravity feedback is dependent on the angular position of the mechanism, such as an arm. The gravity feedback output will vary depending on the mechanism angular position. Note that the sensor offset and ratios must be configured so that the sensor reports a position of 0 when the mechanism is horizonal (parallel to the ground), and the reported sensor position is 1:1 with the mechanism.
-
StaticFeedforwardSign
Static feedforward sign during position closed loop.This determines the sign of the applied kS during position closed-loop modes. The default behavior uses the velocity reference sign. This works well with velocity closed loop, Motion Magic® controls, and position closed loop when velocity reference is specified (motion profiling).
However, when using position closed loop with zero velocity reference (no motion profiling), the application may want to apply static feedforward based on the sign of closed loop error instead. When doing so, we recommend using the minimal amount of kS, otherwise the motor output may dither when closed loop error is near zero.
-
GravityArmPositionOffset
Gravity feedback position offset when using the Arm/Cosine gravity type.This is an offset applied to the position of the arm, within (-0.25, 0.25) rot, before calculating the output of kG. This is useful when the center of gravity of the arm is offset from the actual zero point of the arm, such as when the arm and intake form an L shape.
- Minimum Value: -0.25
- Maximum Value: 0.25
- Default Value: 0
- Units: rotations
-
GainSchedBehavior
The behavior of the gain scheduler on this slot. This specifies which gains to use while within the configured GainSchedErrorThreshold. The default is to continue using the specified slot.Gain scheduling will not take effect when running velocity closed-loop controls.
-
-
Constructor Details
-
Slot0Configs
public Slot0Configs()
-
-
Method Details
-
withKP
Modifies this configuration's kP parameter and returns itself for method-chaining and easier to use config API.Proportional gain.
The units for this gain is dependent on the control mode. Since this gain is multiplied by error in the input, the units should be defined as units of output per unit of input error. For example, when controlling velocity using a duty cycle closed loop, the units for the proportional gain will be duty cycle per rps of error, or 1/rps.
- Minimum Value: 0
- Maximum Value: 3.4e+38
- Default Value: 0
- Units:
- Parameters:
newKP- Parameter to modify- Returns:
- Itself
-
withKI
Modifies this configuration's kI parameter and returns itself for method-chaining and easier to use config API.Integral gain.
The units for this gain is dependent on the control mode. Since this gain is multiplied by error in the input integrated over time (in units of seconds), the units should be defined as units of output per unit of integrated input error. For example, when controlling velocity using a duty cycle closed loop, integrating velocity over time results in rps * s = rotations. Therefore, the units for the integral gain will be duty cycle per rotation of accumulated error, or 1/rot.
- Minimum Value: 0
- Maximum Value: 3.4e+38
- Default Value: 0
- Units:
- Parameters:
newKI- Parameter to modify- Returns:
- Itself
-
withKD
Modifies this configuration's kD parameter and returns itself for method-chaining and easier to use config API.Derivative gain.
The units for this gain is dependent on the control mode. Since this gain is multiplied by the derivative of error in the input with respect to time (in units of seconds), the units should be defined as units of output per unit of the differentiated input error. For example, when controlling velocity using a duty cycle closed loop, the derivative of velocity with respect to time is rot per sec², which is acceleration. Therefore, the units for the derivative gain will be duty cycle per unit of acceleration error, or 1/(rot per sec²).
- Minimum Value: 0
- Maximum Value: 3.4e+38
- Default Value: 0
- Units:
- Parameters:
newKD- Parameter to modify- Returns:
- Itself
-
withKS
Modifies this configuration's kS parameter and returns itself for method-chaining and easier to use config API.Static feedforward gain.
This is added to the closed loop output. The unit for this constant is dependent on the control mode, typically fractional duty cycle, voltage, or torque current.
The sign is typically determined by reference velocity when using position, velocity, and Motion Magic® closed loop modes. However, when using position closed loop with zero velocity reference (no motion profiling), the application can instead use the position closed loop error by setting the Static Feedforward Sign configuration parameter. When doing so, we recommend the minimal amount of kS, otherwise the motor output may dither when closed loop error is near zero.
- Minimum Value: -128
- Maximum Value: 127
- Default Value: 0
- Units:
- Parameters:
newKS- Parameter to modify- Returns:
- Itself
-
withKV
Modifies this configuration's kV parameter and returns itself for method-chaining and easier to use config API.Velocity feedforward gain.
The units for this gain is dependent on the control mode. Since this gain is multiplied by the requested velocity, the units should be defined as units of output per unit of requested input velocity. For example, when controlling velocity using a duty cycle closed loop, the units for the velocity feedfoward gain will be duty cycle per requested rps, or 1/rps.
- Minimum Value: 0
- Maximum Value: 3.4e+38
- Default Value: 0
- Units:
- Parameters:
newKV- Parameter to modify- Returns:
- Itself
-
withKA
Modifies this configuration's kA parameter and returns itself for method-chaining and easier to use config API.Acceleration feedforward gain.
The units for this gain is dependent on the control mode. Since this gain is multiplied by the requested acceleration, the units should be defined as units of output per unit of requested input acceleration. For example, when controlling velocity using a duty cycle closed loop, the units for the acceleration feedfoward gain will be duty cycle per requested rot per sec², or 1/(rot per sec²).
- Minimum Value: 0
- Maximum Value: 3.4e+38
- Default Value: 0
- Units:
- Parameters:
newKA- Parameter to modify- Returns:
- Itself
-
withKG
Modifies this configuration's kG parameter and returns itself for method-chaining and easier to use config API.Gravity feedforward/feedback gain. The type of gravity compensation is selected by
GravityType.This is added to the closed loop output. The sign is determined by the gravity type. The unit for this constant is dependent on the control mode, typically fractional duty cycle, voltage, or torque current.
- Minimum Value: -128
- Maximum Value: 127
- Default Value: 0
- Units:
- Parameters:
newKG- Parameter to modify- Returns:
- Itself
-
withGravityType
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier to use config API.Gravity feedforward/feedback type.
This determines the type of the gravity feedforward/feedback.
Choose Elevator_Static for systems where the gravity feedforward is constant, such as an elevator. The gravity feedforward output will always have the same sign.
Choose Arm_Cosine for systems where the gravity feedback is dependent on the angular position of the mechanism, such as an arm. The gravity feedback output will vary depending on the mechanism angular position. Note that the sensor offset and ratios must be configured so that the sensor reports a position of 0 when the mechanism is horizonal (parallel to the ground), and the reported sensor position is 1:1 with the mechanism.
- Parameters:
newGravityType- Parameter to modify- Returns:
- Itself
-
withStaticFeedforwardSign
public final Slot0Configs withStaticFeedforwardSign(StaticFeedforwardSignValue newStaticFeedforwardSign) Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining and easier to use config API.Static feedforward sign during position closed loop.
This determines the sign of the applied kS during position closed-loop modes. The default behavior uses the velocity reference sign. This works well with velocity closed loop, Motion Magic® controls, and position closed loop when velocity reference is specified (motion profiling).
However, when using position closed loop with zero velocity reference (no motion profiling), the application may want to apply static feedforward based on the sign of closed loop error instead. When doing so, we recommend using the minimal amount of kS, otherwise the motor output may dither when closed loop error is near zero.
- Parameters:
newStaticFeedforwardSign- Parameter to modify- Returns:
- Itself
-
withGravityArmPositionOffset
Modifies this configuration's GravityArmPositionOffset parameter and returns itself for method-chaining and easier to use config API.Gravity feedback position offset when using the Arm/Cosine gravity type.
This is an offset applied to the position of the arm, within (-0.25, 0.25) rot, before calculating the output of kG. This is useful when the center of gravity of the arm is offset from the actual zero point of the arm, such as when the arm and intake form an L shape.
- Minimum Value: -0.25
- Maximum Value: 0.25
- Default Value: 0
- Units: rotations
- Parameters:
newGravityArmPositionOffset- Parameter to modify- Returns:
- Itself
-
withGravityArmPositionOffset
Modifies this configuration's GravityArmPositionOffset parameter and returns itself for method-chaining and easier to use config API.Gravity feedback position offset when using the Arm/Cosine gravity type.
This is an offset applied to the position of the arm, within (-0.25, 0.25) rot, before calculating the output of kG. This is useful when the center of gravity of the arm is offset from the actual zero point of the arm, such as when the arm and intake form an L shape.
- Minimum Value: -0.25
- Maximum Value: 0.25
- Default Value: 0
- Units: rotations
- Parameters:
newGravityArmPositionOffset- Parameter to modify- Returns:
- Itself
-
getGravityArmPositionOffsetMeasure
Helper method to get this configuration's GravityArmPositionOffset parameter converted to a unit type. If not using the Java units library,GravityArmPositionOffsetcan be accessed directly instead.Gravity feedback position offset when using the Arm/Cosine gravity type.
This is an offset applied to the position of the arm, within (-0.25, 0.25) rot, before calculating the output of kG. This is useful when the center of gravity of the arm is offset from the actual zero point of the arm, such as when the arm and intake form an L shape.
- Minimum Value: -0.25
- Maximum Value: 0.25
- Default Value: 0
- Units: rotations
- Returns:
- GravityArmPositionOffset
-
withGainSchedBehavior
Modifies this configuration's GainSchedBehavior parameter and returns itself for method-chaining and easier to use config API.The behavior of the gain scheduler on this slot. This specifies which gains to use while within the configured GainSchedErrorThreshold. The default is to continue using the specified slot.
Gain scheduling will not take effect when running velocity closed-loop controls.
- Parameters:
newGainSchedBehavior- Parameter to modify- Returns:
- Itself
-
from
Converts the provided value to an instance of this type.- Parameters:
value- The value to convert- Returns:
- Converted value
-
toString
-
serialize
Get the serialized form of this configuration group.- Specified by:
serializein interfaceISerializable- Returns:
- Serialized form of this config group
-
deserialize
Take a string and deserialize it to this configuration group.- Specified by:
deserializein interfaceParentConfiguration- Returns:
- Return code of the deserialize method
-
clone
-