mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-17 13:25:27 +03:00
Get setting default values from settings.yaml (#6595)
* Get setting default values from settings.yaml * settings: Make the generator more robust and versatile - Add support for resolving types and values in multiple compilers - Add support for resolving types and values in clang 10 - Add support for using the host compiler for resolving the settings This allows us to run the generator for the unit tests, since they now need the settings_generated.h file to get the default setting values from it. * Fix regexps in settings.rb and add execution bit * Fix git revision issue * Fix issue with settings validation * Fix issue with targets not defining USE_MAG Co-authored-by: Alberto García Hierro <alberto@garciahierro.com>
This commit is contained in:
parent
7b705bccac
commit
fc0e5e2741
85 changed files with 1708 additions and 1875 deletions
|
@ -39,6 +39,7 @@
|
|||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_modes.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/settings.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
|
@ -97,92 +98,96 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
|||
.general = {
|
||||
|
||||
.flags = {
|
||||
.use_thr_mid_for_althold = 0,
|
||||
.extra_arming_safety = NAV_EXTRA_ARMING_SAFETY_ON,
|
||||
.user_control_mode = NAV_GPS_ATTI,
|
||||
.rth_alt_control_mode = NAV_RTH_AT_LEAST_ALT,
|
||||
.rth_climb_first = 1, // Climb first, turn after reaching safe altitude
|
||||
.rth_climb_ignore_emerg = 0, // Ignore GPS loss on initial climb
|
||||
.rth_tail_first = 0,
|
||||
.disarm_on_landing = 0,
|
||||
.rth_allow_landing = NAV_RTH_ALLOW_LANDING_ALWAYS,
|
||||
.nav_overrides_motor_stop = NOMS_ALL_NAV,
|
||||
.use_thr_mid_for_althold = SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_DEFAULT,
|
||||
.extra_arming_safety = SETTING_NAV_EXTRA_ARMING_SAFETY_DEFAULT,
|
||||
.user_control_mode = SETTING_NAV_USER_CONTROL_MODE_DEFAULT,
|
||||
.rth_alt_control_mode = SETTING_NAV_RTH_ALT_MODE_DEFAULT,
|
||||
.rth_climb_first = SETTING_NAV_RTH_CLIMB_FIRST_DEFAULT, // Climb first, turn after reaching safe altitude
|
||||
.rth_climb_ignore_emerg = SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_DEFAULT, // Ignore GPS loss on initial climb
|
||||
.rth_tail_first = SETTING_NAV_RTH_TAIL_FIRST_DEFAULT,
|
||||
.disarm_on_landing = SETTING_NAV_DISARM_ON_LANDING_DEFAULT,
|
||||
.rth_allow_landing = SETTING_NAV_RTH_ALLOW_LANDING_DEFAULT,
|
||||
.nav_overrides_motor_stop = SETTING_NAV_OVERRIDES_MOTOR_STOP_DEFAULT,
|
||||
},
|
||||
|
||||
// General navigation parameters
|
||||
.pos_failure_timeout = 5, // 5 sec
|
||||
.waypoint_radius = 100, // 2m diameter
|
||||
.waypoint_safe_distance = 10000, // centimeters - first waypoint should be closer than this
|
||||
.max_auto_speed = 300, // 3 m/s = 10.8 km/h
|
||||
.max_auto_climb_rate = 500, // 5 m/s
|
||||
.max_manual_speed = 500,
|
||||
.max_manual_climb_rate = 200,
|
||||
.land_descent_rate = 200, // centimeters/s
|
||||
.land_slowdown_minalt = 500, // altitude in centimeters
|
||||
.land_slowdown_maxalt = 2000, // altitude in meters
|
||||
.emerg_descent_rate = 500, // centimeters/s
|
||||
.min_rth_distance = 500, // centimeters, if closer than this land immediately
|
||||
.rth_altitude = 1000, // altitude in centimeters
|
||||
.rth_home_altitude = 0, // altitude in centimeters
|
||||
.rth_abort_threshold = 50000, // centimeters - 500m should be safe for all aircraft
|
||||
.max_terrain_follow_altitude = 100, // max altitude in centimeters in terrain following mode
|
||||
.safehome_max_distance = 20000, // Max distance that a safehome is from the arming point
|
||||
.pos_failure_timeout = SETTING_NAV_POSITION_TIMEOUT_DEFAULT, // 5 sec
|
||||
.waypoint_radius = SETTING_NAV_WP_RADIUS_DEFAULT, // 2m diameter
|
||||
.waypoint_safe_distance = SETTING_NAV_WP_SAFE_DISTANCE_DEFAULT, // centimeters - first waypoint should be closer than this
|
||||
.max_auto_speed = SETTING_NAV_AUTO_SPEED_DEFAULT, // 3 m/s = 10.8 km/h
|
||||
.max_auto_climb_rate = SETTING_NAV_AUTO_CLIMB_RATE_DEFAULT, // 5 m/s
|
||||
.max_manual_speed = SETTING_NAV_MANUAL_SPEED_DEFAULT,
|
||||
.max_manual_climb_rate = SETTING_NAV_MANUAL_CLIMB_RATE_DEFAULT,
|
||||
.land_descent_rate = SETTING_NAV_LANDING_SPEED_DEFAULT, // centimeters/s
|
||||
.land_slowdown_minalt = SETTING_NAV_LAND_SLOWDOWN_MINALT_DEFAULT, // altitude in centimeters
|
||||
.land_slowdown_maxalt = SETTING_NAV_LAND_SLOWDOWN_MAXALT_DEFAULT, // altitude in meters
|
||||
.emerg_descent_rate = SETTING_NAV_EMERG_LANDING_SPEED_DEFAULT, // centimeters/s
|
||||
.min_rth_distance = SETTING_NAV_MIN_RTH_DISTANCE_DEFAULT, // centimeters, if closer than this land immediately
|
||||
.rth_altitude = SETTING_NAV_RTH_ALTITUDE_DEFAULT, // altitude in centimeters
|
||||
.rth_home_altitude = SETTING_NAV_RTH_HOME_ALTITUDE_DEFAULT, // altitude in centimeters
|
||||
.rth_abort_threshold = SETTING_NAV_RTH_ABORT_THRESHOLD_DEFAULT, // centimeters - 500m should be safe for all aircraft
|
||||
.max_terrain_follow_altitude = SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_DEFAULT, // max altitude in centimeters in terrain following mode
|
||||
.safehome_max_distance = SETTING_SAFEHOME_MAX_DISTANCE_DEFAULT, // Max distance that a safehome is from the arming point
|
||||
},
|
||||
|
||||
// MC-specific
|
||||
.mc = {
|
||||
.max_bank_angle = 30, // degrees
|
||||
.hover_throttle = 1500,
|
||||
.auto_disarm_delay = 2000, // milliseconds - time before disarming when auto disarm is enabled and landing is confirmed
|
||||
.braking_speed_threshold = 100, // Braking can become active above 1m/s
|
||||
.braking_disengage_speed = 75, // Stop when speed goes below 0.75m/s
|
||||
.braking_timeout = 2000, // Timeout barking after 2s
|
||||
.braking_boost_factor = 100, // A 100% boost by default
|
||||
.braking_boost_timeout = 750, // Timout boost after 750ms
|
||||
.braking_boost_speed_threshold = 150, // Boost can happen only above 1.5m/s
|
||||
.braking_boost_disengage_speed = 100, // Disable boost at 1m/s
|
||||
.braking_bank_angle = 40, // Max braking angle
|
||||
.posDecelerationTime = 120, // posDecelerationTime * 100
|
||||
.posResponseExpo = 10, // posResponseExpo * 100
|
||||
.slowDownForTurning = true,
|
||||
.max_bank_angle = SETTING_NAV_MC_BANK_ANGLE_DEFAULT, // degrees
|
||||
.hover_throttle = SETTING_NAV_MC_HOVER_THR_DEFAULT,
|
||||
.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
|
||||
.braking_speed_threshold = SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_DEFAULT, // Braking can become active above 1m/s
|
||||
.braking_disengage_speed = SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_DEFAULT, // Stop when speed goes below 0.75m/s
|
||||
.braking_timeout = SETTING_NAV_MC_BRAKING_TIMEOUT_DEFAULT, // Timeout barking after 2s
|
||||
.braking_boost_factor = SETTING_NAV_MC_BRAKING_BOOST_FACTOR_DEFAULT, // A 100% boost by default
|
||||
.braking_boost_timeout = SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_DEFAULT, // Timout boost after 750ms
|
||||
.braking_boost_speed_threshold = SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_DEFAULT, // Boost can happen only above 1.5m/s
|
||||
.braking_boost_disengage_speed = SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_DEFAULT, // Disable boost at 1m/s
|
||||
.braking_bank_angle = SETTING_NAV_MC_BRAKING_BANK_ANGLE_DEFAULT, // Max braking angle
|
||||
#endif
|
||||
|
||||
.posDecelerationTime = SETTING_NAV_MC_POS_DECELERATION_TIME_DEFAULT, // posDecelerationTime * 100
|
||||
.posResponseExpo = SETTING_NAV_MC_POS_EXPO_DEFAULT, // posResponseExpo * 100
|
||||
.slowDownForTurning = SETTING_NAV_MC_WP_SLOWDOWN_DEFAULT,
|
||||
},
|
||||
|
||||
// Fixed wing
|
||||
.fw = {
|
||||
.max_bank_angle = 35, // degrees
|
||||
.max_climb_angle = 20, // degrees
|
||||
.max_dive_angle = 15, // degrees
|
||||
.cruise_throttle = 1400,
|
||||
.cruise_speed = 0, // cm/s
|
||||
.control_smoothness = 0,
|
||||
.max_throttle = 1700,
|
||||
.min_throttle = 1200,
|
||||
.pitch_to_throttle = 10, // pwm units per degree of pitch (10pwm units ~ 1% throttle)
|
||||
.pitch_to_throttle_smooth = 6,
|
||||
.pitch_to_throttle_thresh = 50,
|
||||
.loiter_radius = 7500, // 75m
|
||||
.max_bank_angle = SETTING_NAV_FW_BANK_ANGLE_DEFAULT, // degrees
|
||||
.max_climb_angle = SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT, // degrees
|
||||
.max_dive_angle = SETTING_NAV_FW_DIVE_ANGLE_DEFAULT, // degrees
|
||||
.cruise_throttle = SETTING_NAV_FW_CRUISE_THR_DEFAULT,
|
||||
.cruise_speed = SETTING_NAV_FW_CRUISE_SPEED_DEFAULT, // cm/s
|
||||
.control_smoothness = SETTING_NAV_FW_CONTROL_SMOOTHNESS_DEFAULT,
|
||||
.max_throttle = SETTING_NAV_FW_MAX_THR_DEFAULT,
|
||||
.min_throttle = SETTING_NAV_FW_MIN_THR_DEFAULT,
|
||||
.pitch_to_throttle = SETTING_NAV_FW_PITCH2THR_DEFAULT, // pwm units per degree of pitch (10pwm units ~ 1% throttle)
|
||||
.pitch_to_throttle_smooth = SETTING_NAV_FW_PITCH2THR_SMOOTHING_DEFAULT,
|
||||
.pitch_to_throttle_thresh = SETTING_NAV_FW_PITCH2THR_THRESHOLD_DEFAULT,
|
||||
.loiter_radius = SETTING_NAV_FW_LOITER_RADIUS_DEFAULT, // 75m
|
||||
|
||||
//Fixed wing landing
|
||||
.land_dive_angle = 2, // 2 degrees dive by default
|
||||
.land_dive_angle = SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT, // 2 degrees dive by default
|
||||
|
||||
// Fixed wing launch
|
||||
.launch_velocity_thresh = 300, // 3 m/s
|
||||
.launch_accel_thresh = 1.9f * 981, // cm/s/s (1.9*G)
|
||||
.launch_time_thresh = 40, // 40ms
|
||||
.launch_throttle = 1700,
|
||||
.launch_idle_throttle = 1000, // Motor idle or MOTOR_STOP
|
||||
.launch_motor_timer = 500, // ms
|
||||
.launch_motor_spinup_time = 100, // ms, time to gredually increase throttle from idle to launch
|
||||
.launch_end_time = 3000, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode
|
||||
.launch_min_time = 0, // ms, min time in launch mode
|
||||
.launch_timeout = 5000, // ms, timeout for launch procedure
|
||||
.launch_max_altitude = 0, // cm, altitude where to consider launch ended
|
||||
.launch_climb_angle = 18, // 18 degrees
|
||||
.launch_max_angle = 45, // 45 deg
|
||||
.cruise_yaw_rate = 20, // 20dps
|
||||
.allow_manual_thr_increase = false,
|
||||
.useFwNavYawControl = 0,
|
||||
.yawControlDeadband = 0,
|
||||
.launch_velocity_thresh = SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT, // 3 m/s
|
||||
.launch_accel_thresh = SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT, // cm/s/s (1.9*G)
|
||||
.launch_time_thresh = SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT, // 40ms
|
||||
.launch_throttle = SETTING_NAV_FW_LAUNCH_THR_DEFAULT,
|
||||
.launch_idle_throttle = SETTING_NAV_FW_LAUNCH_IDLE_THR_DEFAULT, // Motor idle or MOTOR_STOP
|
||||
.launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms
|
||||
.launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to gredually increase throttle from idle to launch
|
||||
.launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode
|
||||
.launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode
|
||||
.launch_timeout = SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT, // ms, timeout for launch procedure
|
||||
.launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended
|
||||
.launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees
|
||||
.launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg
|
||||
.cruise_yaw_rate = SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT, // 20dps
|
||||
.allow_manual_thr_increase = SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT,
|
||||
.useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT,
|
||||
.yawControlDeadband = SETTING_NAV_FW_YAW_DEADBAND_DEFAULT,
|
||||
}
|
||||
);
|
||||
|
||||
|
@ -3432,7 +3437,10 @@ void navigationUsePIDs(void)
|
|||
multicopterPosXyCoefficients.dTermAttenuation = pidProfile()->navVelXyDtermAttenuation / 100.0f;
|
||||
multicopterPosXyCoefficients.dTermAttenuationStart = pidProfile()->navVelXyDtermAttenuationStart / 100.0f;
|
||||
multicopterPosXyCoefficients.dTermAttenuationEnd = pidProfile()->navVelXyDtermAttenuationEnd / 100.0f;
|
||||
|
||||
#ifdef USE_MR_BRAKING_MODE
|
||||
multicopterPosXyCoefficients.breakingBoostFactor = (float) navConfig()->mc.braking_boost_factor / 100.0f;
|
||||
#endif
|
||||
|
||||
// Initialize altitude hold PID-controllers (pos_z, vel_z, acc_z
|
||||
navPidInit(
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue