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

remove duplicate settings

This commit is contained in:
breadoven 2022-09-27 21:42:31 +01:00
parent 16be85975a
commit 0fb8897eb9
6 changed files with 17 additions and 35 deletions

View file

@ -2812,6 +2812,16 @@ Maximum climb/descent rate that UAV is allowed to reach during navigation modes.
--- ---
### nav_auto_disarm_delay
Delay before craft disarms when `nav_disarm_on_landing` is set (ms)
| Default | Min | Max |
| --- | --- | --- |
| 2000 | 100 | 10000 |
---
### nav_auto_speed ### nav_auto_speed
Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only] Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only]
@ -2862,16 +2872,6 @@ Enable the possibility to manually increase the throttle in auto throttle contro
--- ---
### nav_fw_auto_disarm_delay
Delay before plane disarms when `nav_disarm_on_landing` is set (ms)
| Default | Min | Max |
| --- | --- | --- |
| 2000 | 100 | 10000 |
---
### nav_fw_bank_angle ### nav_fw_bank_angle
Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll
@ -3442,16 +3442,6 @@ Max allowed above the ground altitude for terrain following mode
--- ---
### nav_mc_auto_disarm_delay
Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (ms)
| Default | Min | Max |
| --- | --- | --- |
| 2000 | 100 | 10000 |
---
### nav_mc_bank_angle ### nav_mc_bank_angle
Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude

View file

@ -2653,10 +2653,10 @@ groups:
field: mc.max_bank_angle field: mc.max_bank_angle
min: 15 min: 15
max: 45 max: 45
- name: nav_mc_auto_disarm_delay - name: nav_auto_disarm_delay
description: "Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (ms)" description: "Delay before craft disarms when `nav_disarm_on_landing` is set (ms)"
default_value: 2000 default_value: 2000
field: mc.auto_disarm_delay field: general.auto_disarm_delay
min: 100 min: 100
max: 10000 max: 10000
- name: nav_mc_braking_speed_threshold - name: nav_mc_braking_speed_threshold
@ -2732,12 +2732,6 @@ groups:
default_value: ON default_value: ON
field: mc.slowDownForTurning field: mc.slowDownForTurning
type: bool type: bool
- name: nav_fw_auto_disarm_delay
description: "Delay before plane disarms when `nav_disarm_on_landing` is set (ms)"
default_value: 2000
field: fw.auto_disarm_delay
min: 100
max: 10000
- name: nav_fw_bank_angle - name: nav_fw_bank_angle
description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll" description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll"
default_value: 35 default_value: 35

View file

@ -153,12 +153,12 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.rth_trackback_distance = SETTING_NAV_RTH_TRACKBACK_DISTANCE_DEFAULT, // Max distance allowed for RTH trackback .rth_trackback_distance = SETTING_NAV_RTH_TRACKBACK_DISTANCE_DEFAULT, // Max distance allowed for RTH trackback
.waypoint_enforce_altitude = SETTING_NAV_WP_ENFORCE_ALTITUDE_DEFAULT, // Forces set wp altitude to be achieved .waypoint_enforce_altitude = SETTING_NAV_WP_ENFORCE_ALTITUDE_DEFAULT, // Forces set wp altitude to be achieved
.land_detect_sensitivity = SETTING_NAV_LAND_DETECT_SENSITIVITY_DEFAULT, // Changes sensitivity of landing detection .land_detect_sensitivity = SETTING_NAV_LAND_DETECT_SENSITIVITY_DEFAULT, // Changes sensitivity of landing detection
.auto_disarm_delay = SETTING_NAV_AUTO_DISARM_DELAY_DEFAULT, // 2000 ms - time delay to disarm when auto disarm after landing enabled
}, },
// MC-specific // MC-specific
.mc = { .mc = {
.max_bank_angle = SETTING_NAV_MC_BANK_ANGLE_DEFAULT, // degrees .max_bank_angle = SETTING_NAV_MC_BANK_ANGLE_DEFAULT, // degrees
.auto_disarm_delay = SETTING_NAV_MC_AUTO_DISARM_DELAY_DEFAULT, // milliseconds - time before disarming when auto disarm is enabled and landing is confirmed
#ifdef USE_MR_BRAKING_MODE #ifdef USE_MR_BRAKING_MODE
.braking_speed_threshold = SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_DEFAULT, // Braking can become active above 1m/s .braking_speed_threshold = SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_DEFAULT, // Braking can become active above 1m/s
@ -211,7 +211,6 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT, .useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT,
.yawControlDeadband = SETTING_NAV_FW_YAW_DEADBAND_DEFAULT, .yawControlDeadband = SETTING_NAV_FW_YAW_DEADBAND_DEFAULT,
.soaring_pitch_deadband = SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT,// pitch angle mode deadband when Saoring mode enabled .soaring_pitch_deadband = SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT,// pitch angle mode deadband when Saoring mode enabled
.auto_disarm_delay = SETTING_NAV_FW_AUTO_DISARM_DELAY_DEFAULT, // ms - time delay to disarm when auto disarm after landing enabled
.wp_tracking_accuracy = SETTING_NAV_FW_WP_TRACKING_ACCURACY_DEFAULT, // 0, improves course tracking accuracy during FW WP missions .wp_tracking_accuracy = SETTING_NAV_FW_WP_TRACKING_ACCURACY_DEFAULT, // 0, improves course tracking accuracy during FW WP missions
.wp_tracking_max_angle = SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_DEFAULT, // 60 degs .wp_tracking_max_angle = SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_DEFAULT, // 60 degs
.wp_turn_smoothing = SETTING_NAV_FW_WP_TURN_SMOOTHING_DEFAULT, // 0, smooths turns during FW WP mode missions .wp_turn_smoothing = SETTING_NAV_FW_WP_TURN_SMOOTHING_DEFAULT, // 0, smooths turns during FW WP mode missions

View file

@ -264,11 +264,11 @@ typedef struct navConfig_s {
uint16_t rth_trackback_distance; // RTH trackback maximum distance [m] uint16_t rth_trackback_distance; // RTH trackback maximum distance [m]
uint16_t waypoint_enforce_altitude; // Forces waypoint altitude to be achieved uint16_t waypoint_enforce_altitude; // Forces waypoint altitude to be achieved
uint8_t land_detect_sensitivity; // Sensitivity of landing detector uint8_t land_detect_sensitivity; // Sensitivity of landing detector
uint16_t auto_disarm_delay; // safety time delay for landing detector
} general; } general;
struct { struct {
uint8_t max_bank_angle; // multicopter max banking angle (deg) uint8_t max_bank_angle; // multicopter max banking angle (deg)
uint16_t auto_disarm_delay; // multicopter safety delay for landing detector
#ifdef USE_MR_BRAKING_MODE #ifdef USE_MR_BRAKING_MODE
uint16_t braking_speed_threshold; // above this speed braking routine might kick in uint16_t braking_speed_threshold; // above this speed braking routine might kick in
@ -315,7 +315,6 @@ typedef struct navConfig_s {
bool useFwNavYawControl; bool useFwNavYawControl;
uint8_t yawControlDeadband; uint8_t yawControlDeadband;
uint8_t soaring_pitch_deadband; // soaring mode pitch angle deadband (deg) uint8_t soaring_pitch_deadband; // soaring mode pitch angle deadband (deg)
uint16_t auto_disarm_delay; // fixed wing disarm delay for landing detector
uint8_t wp_tracking_accuracy; // fixed wing tracking accuracy response factor uint8_t wp_tracking_accuracy; // fixed wing tracking accuracy response factor
uint8_t wp_tracking_max_angle; // fixed wing tracking accuracy max alignment angle [degs] uint8_t wp_tracking_max_angle; // fixed wing tracking accuracy max alignment angle [degs]
uint8_t wp_turn_smoothing; // WP mission turn smoothing options uint8_t wp_turn_smoothing; // WP mission turn smoothing options

View file

@ -723,7 +723,7 @@ bool isFixedWingLandingDetected(void)
DEBUG_SET(DEBUG_LANDING, 7, isPitchAxisStatic); DEBUG_SET(DEBUG_LANDING, 7, isPitchAxisStatic);
if (isRollAxisStatic && isPitchAxisStatic) { if (isRollAxisStatic && isPitchAxisStatic) {
// Probably landed, low horizontal and vertical velocities and no axis rotation in Roll and Pitch // Probably landed, low horizontal and vertical velocities and no axis rotation in Roll and Pitch
timeMs_t safetyTimeDelay = 2000 + navConfig()->fw.auto_disarm_delay; timeMs_t safetyTimeDelay = 2000 + navConfig()->general.auto_disarm_delay;
return currentTimeMs - fwLandingTimerStartAt > safetyTimeDelay; // check conditions stable for 2s + optional extra delay return currentTimeMs - fwLandingTimerStartAt > safetyTimeDelay; // check conditions stable for 2s + optional extra delay
} else { } else {
fixAxisCheck = false; fixAxisCheck = false;

View file

@ -799,7 +799,7 @@ bool isMulticopterLandingDetected(void)
DEBUG_SET(DEBUG_LANDING, 5, possibleLandingDetected); DEBUG_SET(DEBUG_LANDING, 5, possibleLandingDetected);
if (possibleLandingDetected) { if (possibleLandingDetected) {
timeUs_t safetyTimeDelay = MS2US(2000 + navConfig()->mc.auto_disarm_delay); // check conditions stable for 2s + optional extra delay timeUs_t safetyTimeDelay = MS2US(2000 + navConfig()->general.auto_disarm_delay); // check conditions stable for 2s + optional extra delay
return (currentTimeUs - landingDetectorStartedAt > safetyTimeDelay); return (currentTimeUs - landingDetectorStartedAt > safetyTimeDelay);
} else { } else {
landingDetectorStartedAt = currentTimeUs; landingDetectorStartedAt = currentTimeUs;