Class Slot1Configs
- All Implemented Interfaces:
ParentConfiguration
,ISerializable
If this slot is selected, these gains are used in closed loop control requests.
-
Field Summary
FieldsModifier and TypeFieldDescriptionGravity Feedforward/Feedback Type.double
Acceleration Feedforward Gain.double
Derivative Gain.double
Gravity Feedforward/Feedback Gain.double
Integral Gain.double
Proportional Gain.double
Static Feedforward Gain.double
Velocity Feedforward Gain.Static Feedforward Sign during position closed loop. -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptiondeserialize
(String to_deserialize) static Slot1Configs
from
(SlotConfigs value) toString()
withGravityType
(GravityTypeValue newGravityType) Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier to use config API.withKA
(double newKA) Modifies this configuration's kA parameter and returns itself for method-chaining and easier to use config API.withKD
(double newKD) Modifies this configuration's kD parameter and returns itself for method-chaining and easier to use config API.withKG
(double newKG) Modifies this configuration's kG parameter and returns itself for method-chaining and easier to use config API.withKI
(double newKI) Modifies this configuration's kI parameter and returns itself for method-chaining and easier to use config API.withKP
(double newKP) Modifies this configuration's kP parameter and returns itself for method-chaining and easier to use config API.withKS
(double newKS) Modifies this configuration's kS parameter and returns itself for method-chaining and easier to use config API.withKV
(double newKV) Modifies this configuration's kV parameter and returns itself for method-chaining and easier to use config API.withStaticFeedforwardSign
(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, 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: -512
- Maximum Value: 511
- 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.This is added to the closed loop output. The sign is determined by GravityType. The unit for this constant is dependent on the control mode, typically fractional duty cycle, voltage, or torque current.
- Minimum Value: -512
- Maximum Value: 511
- 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 be positive.
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 position is 0 when the mechanism is horizonal, and one rotation of the mechanism corresponds to one rotation of the sensor position.
-
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 closed loop error sign 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.
-
-
Constructor Details
-
Slot1Configs
public Slot1Configs()
-
-
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, 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: -512
- Maximum Value: 511
- 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.
This is added to the closed loop output. The sign is determined by GravityType. The unit for this constant is dependent on the control mode, typically fractional duty cycle, voltage, or torque current.
- Minimum Value: -512
- Maximum Value: 511
- 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 be positive.
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 position is 0 when the mechanism is horizonal, and one rotation of the mechanism corresponds to one rotation of the sensor position.
- Parameters:
newGravityType
- Parameter to modify- Returns:
- Itself
-
withStaticFeedforwardSign
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 closed loop error sign 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
-
from
-
toString
-
deserialize
- Specified by:
deserialize
in interfaceParentConfiguration
-
serialize
- Specified by:
serialize
in interfaceISerializable
-