1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 00:05:28 +03:00

Remove unnecessary parameters from profiles

`fw_loiter_direction` was in control profiles. There's no reason why this would want to be changed with different control parameters. It's purely a pilot preference. This has been moved to `navConfig.fw`

'fw_min_throttle_down_pitch` was in the battery profiles. This command is really something that is set based on the airframe and it's glide ratio. Battery type or performance does not effect this. Moved to `navConfig.fw`
This commit is contained in:
Darren Lines 2022-10-06 21:36:25 +01:00
parent 054de8f706
commit 541bbd856f
11 changed files with 24 additions and 26 deletions

View file

@ -574,7 +574,7 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t
navigationUsePIDs();
break;
case ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE:
applyAdjustmentU16(ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE, &currentBatteryProfileMutable->fwMinThrottleDownPitchAngle, delta, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MIN, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MAX);
applyAdjustmentU16(ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE, &navConfigMutable()->fw.minThrottleDownPitchAngle, delta, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MIN, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MAX);
break;
#if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)
case ADJUSTMENT_VTX_POWER_LEVEL:

View file

@ -1140,12 +1140,6 @@ groups:
default_value: 1000
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
- name: fw_min_throttle_down_pitch
description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)"
default_value: 0
field: fwMinThrottleDownPitchAngle
min: 0
max: 450
- name: nav_mc_hover_thr
description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering."
default_value: 1500
@ -1915,11 +1909,6 @@ groups:
field: fixedWingItermThrowLimit
min: FW_ITERM_THROW_LIMIT_MIN
max: FW_ITERM_THROW_LIMIT_MAX
- name: fw_loiter_direction
description: "Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick."
default_value: "RIGHT"
field: loiter_direction
table: direction
- name: fw_reference_airspeed
description: "Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present."
default_value: 1500
@ -2756,6 +2745,12 @@ groups:
field: fw.pitch_to_throttle_smooth
min: 0
max: 9
- name: fw_min_throttle_down_pitch
description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)"
default_value: 0
field: fw.minThrottleDownPitchAngle
min: 0
max: 450
- name: nav_fw_pitch2thr_threshold
description: "Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]"
default_value: 50
@ -2768,6 +2763,11 @@ groups:
field: fw.loiter_radius
min: 0
max: 30000
- name: fw_loiter_direction
description: "Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick."
default_value: "RIGHT"
field: fw.loiter_direction
table: direction
- name: nav_fw_cruise_speed
description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s"
default_value: 0

View file

@ -278,7 +278,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
.fixedWingItermLimitOnStickPosition = SETTING_FW_ITERM_LIMIT_STICK_POSITION_DEFAULT,
.fixedWingYawItermBankFreeze = SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_DEFAULT,
.loiter_direction = SETTING_FW_LOITER_DIRECTION_DEFAULT,
.navVelXyDTermLpfHz = SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_DEFAULT,
.navVelXyDtermAttenuation = SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_DEFAULT,
.navVelXyDtermAttenuationStart = SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_DEFAULT,
@ -597,7 +596,7 @@ static float computePidLevelTarget(flight_dynamics_index_t axis) {
// Automatically pitch down if the throttle is manually controlled and reduced bellow cruise throttle
if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle()) {
angleTarget += scaleRange(MAX(0, currentBatteryProfile->nav.fw.cruise_throttle - rcCommand[THROTTLE]), 0, currentBatteryProfile->nav.fw.cruise_throttle - PWM_RANGE_MIN, 0, currentBatteryProfile->fwMinThrottleDownPitchAngle);
angleTarget += scaleRange(MAX(0, currentBatteryProfile->nav.fw.cruise_throttle - rcCommand[THROTTLE]), 0, currentBatteryProfile->nav.fw.cruise_throttle - PWM_RANGE_MIN, 0, navConfig()->fw.minThrottleDownPitchAngle);
}
//PITCH trim applied by a AutoLevel flight mode and manual pitch trimming

View file

@ -133,7 +133,6 @@ typedef struct pidProfile_s {
float fixedWingItermLimitOnStickPosition; //Do not allow Iterm to grow when stick position is above this point
uint16_t fixedWingYawItermBankFreeze; // Freeze yaw Iterm when bank angle is more than this many degrees
uint8_t loiter_direction; // Direction of loitering center point on right wing (clockwise - as before), or center point on left wing (counterclockwise)
float navVelXyDTermLpfHz;
uint8_t navVelXyDtermAttenuation; // VEL_XY dynamic Dterm scale: Dterm will be attenuatedby this value (in percent) when UAV is traveling with more than navVelXyDtermAttenuationStart percents of max velocity
uint8_t navVelXyDtermAttenuationStart; // VEL_XY dynamic Dterm scale: Dterm attenuation will begin at this percent of max velocity

View file

@ -2564,7 +2564,7 @@ static bool osdDrawSingleElement(uint8_t item)
return true;
case OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE:
osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "0TP", 0, (float)currentBatteryProfile->fwMinThrottleDownPitchAngle / 10, 3, 1, ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE);
osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "0TP", 0, (float)navConfig()->fw.minThrottleDownPitchAngle / 10, 3, 1, ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE);
return true;
case OSD_FW_ALT_PID_OUTPUTS:

View file

@ -953,7 +953,7 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction)
tfp_sprintf(buff, "VZD %3d", pidBankMutable()->pid[PID_VEL_Z].D);
break;
case ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE:
tfp_sprintf(buff, "MTDPA %4d", currentBatteryProfileMutable->fwMinThrottleDownPitchAngle);
tfp_sprintf(buff, "MTDPA %4d", navConfigMutable()->fw.minThrottleDownPitchAngle);
break;
case ADJUSTMENT_TPA:
tfp_sprintf(buff, "TPA %3d", currentControlRateProfile->throttle.dynPID);

View file

@ -185,7 +185,9 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.control_smoothness = SETTING_NAV_FW_CONTROL_SMOOTHNESS_DEFAULT,
.pitch_to_throttle_smooth = SETTING_NAV_FW_PITCH2THR_SMOOTHING_DEFAULT,
.pitch_to_throttle_thresh = SETTING_NAV_FW_PITCH2THR_THRESHOLD_DEFAULT,
.minThrottleDownPitchAngle = SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT,
.loiter_radius = SETTING_NAV_FW_LOITER_RADIUS_DEFAULT, // 75m
.loiter_direction = SETTING_FW_LOITER_DIRECTION_DEFAULT,
//Fixed wing landing
.land_dive_angle = SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT, // 2 degrees dive by default

View file

@ -294,7 +294,9 @@ typedef struct navConfig_s {
uint8_t control_smoothness; // The amount of smoothing to apply to controls for navigation
uint16_t pitch_to_throttle_smooth; // How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh.
uint8_t pitch_to_throttle_thresh; // Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]
uint16_t minThrottleDownPitchAngle; // Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle. [decidegrees]
uint16_t loiter_radius; // Loiter radius when executing PH on a fixed wing
uint8_t loiter_direction; // Direction of loitering center point on right wing (clockwise - as before), or center point on left wing (counterclockwise)
int8_t land_dive_angle;
uint16_t launch_velocity_thresh; // Velocity threshold for swing launch detection
uint16_t launch_accel_thresh; // Acceleration threshold for launch detection (cm/s/s)

View file

@ -240,11 +240,11 @@ void resetFixedWingPositionController(void)
static int8_t loiterDirection(void) {
int8_t dir = 1; //NAV_LOITER_RIGHT
if (pidProfile()->loiter_direction == NAV_LOITER_LEFT) {
if (navConfig()->fw.loiter_direction == NAV_LOITER_LEFT) {
dir = -1;
}
if (pidProfile()->loiter_direction == NAV_LOITER_YAW) {
if (navConfig()->fw.loiter_direction == NAV_LOITER_YAW) {
if (rcCommand[YAW] < -250) {
loiterDirYaw = 1; //RIGHT //yaw is contrariwise

View file

@ -130,8 +130,6 @@ void pgResetFn_batteryProfiles(batteryProfile_t *instance)
.failsafe_throttle = SETTING_FAILSAFE_THROTTLE_DEFAULT, // default throttle off.
.fwMinThrottleDownPitchAngle = SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT,
.nav = {
.mc = {

View file

@ -106,8 +106,6 @@ typedef struct batteryProfile_s {
uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500.
uint16_t fwMinThrottleDownPitchAngle;
struct {
struct {