CTRE Phoenix 6 C++ 24.3.0
|
Gains for the specified slot. More...
#include <ctre/phoenix6/configs/Configs.hpp>
Public Member Functions | |
Slot0Configs & | WithKP (double newKP) |
Modifies this configuration's kP parameter and returns itself for method-chaining and easier to use config API. More... | |
Slot0Configs & | WithKI (double newKI) |
Modifies this configuration's kI parameter and returns itself for method-chaining and easier to use config API. More... | |
Slot0Configs & | WithKD (double newKD) |
Modifies this configuration's kD parameter and returns itself for method-chaining and easier to use config API. More... | |
Slot0Configs & | WithKS (double newKS) |
Modifies this configuration's kS parameter and returns itself for method-chaining and easier to use config API. More... | |
Slot0Configs & | WithKV (double newKV) |
Modifies this configuration's kV parameter and returns itself for method-chaining and easier to use config API. More... | |
Slot0Configs & | WithKA (double newKA) |
Modifies this configuration's kA parameter and returns itself for method-chaining and easier to use config API. More... | |
Slot0Configs & | WithKG (double newKG) |
Modifies this configuration's kG parameter and returns itself for method-chaining and easier to use config API. More... | |
Slot0Configs & | WithGravityType (signals::GravityTypeValue newGravityType) |
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier to use config API. More... | |
Slot0Configs & | WithStaticFeedforwardSign (signals::StaticFeedforwardSignValue newStaticFeedforwardSign) |
Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining and easier to use config API. More... | |
std::string | ToString () const override |
std::string | Serialize () const override |
ctre::phoenix::StatusCode | Deserialize (const std::string &to_deserialize) override |
virtual std::string | ToString () const =0 |
virtual ctre::phoenix::StatusCode | Deserialize (const std::string &string)=0 |
virtual std::string | Serialize () const =0 |
Static Public Member Functions | |
static Slot0Configs | From (const SlotConfigs &value) |
Public Attributes | |
double | kP = 0 |
Proportional Gain. More... | |
double | kI = 0 |
Integral Gain. More... | |
double | kD = 0 |
Derivative Gain. More... | |
double | kS = 0 |
Static Feedforward Gain. More... | |
double | kV = 0 |
Velocity Feedforward Gain. More... | |
double | kA = 0 |
Acceleration Feedforward Gain. More... | |
double | kG = 0 |
Gravity Feedforward/Feedback Gain. More... | |
signals::GravityTypeValue | GravityType = signals::GravityTypeValue::Elevator_Static |
Gravity Feedforward/Feedback Type. More... | |
signals::StaticFeedforwardSignValue | StaticFeedforwardSign = signals::StaticFeedforwardSignValue::UseVelocitySign |
Static Feedforward Sign during position closed loop. More... | |
Gains for the specified slot.
If this slot is selected, these gains are used in closed loop control requests.
|
inlineoverridevirtual |
Implements ctre::phoenix6::configs::ParentConfiguration.
|
static |
|
inlineoverridevirtual |
Implements ctre::phoenix6::ISerializable.
|
inlineoverridevirtual |
Implements ctre::phoenix6::configs::ParentConfiguration.
|
inline |
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.
newGravityType | Parameter to modify |
|
inline |
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 rps/s, or 1/(rps/s).
newKA | Parameter to modify |
|
inline |
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 rps/s, which is acceleration. Therefore, the units for the derivative gain will be duty cycle per unit of acceleration error, or 1/(rps/s).
newKD | Parameter to modify |
|
inline |
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.
newKG | Parameter to modify |
|
inline |
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.
newKI | Parameter to modify |
|
inline |
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.
newKP | Parameter to modify |
|
inline |
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.
newKS | Parameter to modify |
|
inline |
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.
newKV | Parameter to modify |
|
inline |
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 the minimal amount of kS, otherwise the motor output may dither when closed loop error is near zero.
newStaticFeedforwardSign | Parameter to modify |
signals::GravityTypeValue ctre::phoenix6::configs::Slot0Configs::GravityType = signals::GravityTypeValue::Elevator_Static |
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.
double ctre::phoenix6::configs::Slot0Configs::kA = 0 |
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 rps/s, or 1/(rps/s).
double ctre::phoenix6::configs::Slot0Configs::kD = 0 |
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 rps/s, which is acceleration. Therefore, the units for the derivative gain will be duty cycle per unit of acceleration error, or 1/(rps/s).
double ctre::phoenix6::configs::Slot0Configs::kG = 0 |
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.
double ctre::phoenix6::configs::Slot0Configs::kI = 0 |
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.
double ctre::phoenix6::configs::Slot0Configs::kP = 0 |
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.
double ctre::phoenix6::configs::Slot0Configs::kS = 0 |
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.
double ctre::phoenix6::configs::Slot0Configs::kV = 0 |
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.
signals::StaticFeedforwardSignValue ctre::phoenix6::configs::Slot0Configs::StaticFeedforwardSign = signals::StaticFeedforwardSignValue::UseVelocitySign |
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 the minimal amount of kS, otherwise the motor output may dither when closed loop error is near zero.