mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
MC acro: add separate params to configure yaw expo
So that it can be customized better according to personal preferences. The limitation of 16 chars did not allow to use a better param name.
This commit is contained in:
parent
58c757a9db
commit
f2cee9970c
@ -220,8 +220,10 @@ private:
|
||||
(ParamFloat<px4::params::MC_ACRO_R_MAX>) _acro_roll_max,
|
||||
(ParamFloat<px4::params::MC_ACRO_P_MAX>) _acro_pitch_max,
|
||||
(ParamFloat<px4::params::MC_ACRO_Y_MAX>) _acro_yaw_max,
|
||||
(ParamFloat<px4::params::MC_ACRO_EXPO>) _acro_expo, /**< function parameter for expo stick curve shape */
|
||||
(ParamFloat<px4::params::MC_ACRO_SUPEXPO>) _acro_superexpo, /**< function parameter for superexpo stick curve shape */
|
||||
(ParamFloat<px4::params::MC_ACRO_EXPO>) _acro_expo_rp, /**< expo stick curve shape (roll & pitch) */
|
||||
(ParamFloat<px4::params::MC_ACRO_EXPO_Y>) _acro_expo_y, /**< expo stick curve shape (yaw) */
|
||||
(ParamFloat<px4::params::MC_ACRO_SUPEXPO>) _acro_superexpo_rp, /**< superexpo stick curve shape (roll & pitch) */
|
||||
(ParamFloat<px4::params::MC_ACRO_SUPEXPOY>) _acro_superexpo_y, /**< superexpo stick curve shape (yaw) */
|
||||
|
||||
(ParamFloat<px4::params::MC_RATT_TH>) _rattitude_thres,
|
||||
|
||||
|
||||
@ -704,9 +704,9 @@ MulticopterAttitudeControl::run()
|
||||
if (_v_control_mode.flag_control_manual_enabled) {
|
||||
/* manual rates control - ACRO mode */
|
||||
Vector3f man_rate_sp(
|
||||
math::superexpo(_manual_control_sp.y, _acro_expo.get(), _acro_superexpo.get()),
|
||||
math::superexpo(-_manual_control_sp.x, _acro_expo.get(), _acro_superexpo.get()),
|
||||
math::superexpo(_manual_control_sp.r, _acro_expo.get(), _acro_superexpo.get()));
|
||||
math::superexpo(_manual_control_sp.y, _acro_expo_rp.get(), _acro_superexpo_rp.get()),
|
||||
math::superexpo(-_manual_control_sp.x, _acro_expo_rp.get(), _acro_superexpo_rp.get()),
|
||||
math::superexpo(_manual_control_sp.r, _acro_expo_y.get(), _acro_superexpo_y.get()));
|
||||
_rates_sp = man_rate_sp.emult(_acro_rate_max);
|
||||
_thrust_sp = _manual_control_sp.z;
|
||||
|
||||
|
||||
@ -381,8 +381,7 @@ PARAM_DEFINE_FLOAT(MC_ACRO_P_MAX, 720.0f);
|
||||
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);
|
||||
|
||||
/**
|
||||
* 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);
|
||||
|
||||
/**
|
||||
* 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);
|
||||
|
||||
/**
|
||||
* Threshold for Rattitude mode
|
||||
*
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user