-
Notifications
You must be signed in to change notification settings - Fork 13.7k
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
MC acro: add separate params to configure yaw expo #9358
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -347,7 +347,7 @@ PARAM_DEFINE_FLOAT(MC_YAWRAUTO_MAX, 45.0f); | |
* | ||
* @unit deg/s | ||
* @min 0.0 | ||
* @max 1000.0 | ||
* @max 1800.0 | ||
* @decimal 1 | ||
* @increment 5 | ||
* @group Multicopter Attitude Control | ||
|
@@ -360,7 +360,7 @@ PARAM_DEFINE_FLOAT(MC_ACRO_R_MAX, 720.0f); | |
* | ||
* @unit deg/s | ||
* @min 0.0 | ||
* @max 1000.0 | ||
* @max 1800.0 | ||
* @decimal 1 | ||
* @increment 5 | ||
* @group Multicopter Attitude Control | ||
|
@@ -373,16 +373,15 @@ PARAM_DEFINE_FLOAT(MC_ACRO_P_MAX, 720.0f); | |
* | ||
* @unit deg/s | ||
* @min 0.0 | ||
* @max 1000.0 | ||
* @max 1800.0 | ||
* @decimal 1 | ||
* @increment 5 | ||
* @group Multicopter Attitude Control | ||
*/ | ||
PARAM_DEFINE_FLOAT(MC_ACRO_Y_MAX, 540.0f); | ||
|
||
/** | ||
* Acro Expo factor | ||
* applied to input of all axis: roll, pitch, yaw | ||
* Acro Expo factor for Roll and Pitch. | ||
* | ||
* 0 Purely linear input curve | ||
* 1 Purely cubic input curve | ||
|
@@ -395,8 +394,20 @@ PARAM_DEFINE_FLOAT(MC_ACRO_Y_MAX, 540.0f); | |
PARAM_DEFINE_FLOAT(MC_ACRO_EXPO, 0.69f); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Should we rename MC_ACRO_EXPO_RP for consistency? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Renaming existing params is a pain, and I try to avoid it if at all possible. We can do it within the scope of a larger refactoring. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I think it should not be that big of a deal in this case. You can change the name if you want. |
||
|
||
/** | ||
* Acro SuperExpo factor | ||
* applied to input of all axis: roll, pitch, yaw | ||
* Acro Expo factor for Yaw. | ||
* | ||
* 0 Purely linear input curve | ||
* 1 Purely cubic input curve | ||
* | ||
* @min 0 | ||
* @max 1 | ||
* @decimal 2 | ||
* @group Multicopter Attitude Control | ||
*/ | ||
PARAM_DEFINE_FLOAT(MC_ACRO_EXPO_Y, 0.69f); | ||
|
||
/** | ||
* Acro SuperExpo factor for Roll and Pitch. | ||
* | ||
* 0 Pure Expo function | ||
* 0.7 resonable shape enhancement for intuitive stick feel | ||
|
@@ -409,6 +420,20 @@ PARAM_DEFINE_FLOAT(MC_ACRO_EXPO, 0.69f); | |
*/ | ||
PARAM_DEFINE_FLOAT(MC_ACRO_SUPEXPO, 0.7f); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. MC_ACRO_SUPEXPO_RP ? |
||
|
||
/** | ||
* Acro SuperExpo factor for Yaw. | ||
* | ||
* 0 Pure Expo function | ||
* 0.7 resonable shape enhancement for intuitive stick feel | ||
* 0.95 very strong bent input curve only near maxima have effect | ||
* | ||
* @min 0 | ||
* @max 0.95 | ||
* @decimal 2 | ||
* @group Multicopter Attitude Control | ||
*/ | ||
PARAM_DEFINE_FLOAT(MC_ACRO_SUPEXPOY, 0.7f); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I would expect this to be MC_ACRO_SUPEXPO_Y for consistency and readability There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. As I wrote:
So yes your suggestion makes more sense, but exceeds the maximum length unfortunately. |
||
|
||
/** | ||
* Threshold for Rattitude mode | ||
* | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Did you do experiements about the overshoot not accidentally breaching the 2000deg/s gyro limit barrier? I don't have experience with >1000 deg/s rates.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
No, not that high, but I did go over 1000. Would be interesting to know indeed.
Looks like others are actually going to the 2000 limit: betaflight/betaflight-configurator#997