AP_TECS: added TECS_OPTIONS

used for full-time glider
This commit is contained in:
Andrew Tridgell 2019-03-02 22:30:06 +11:00
parent df0cc40bba
commit 587aa33617
2 changed files with 13 additions and 1 deletions

View File

@ -242,6 +242,13 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = {
// @User: Advanced
AP_GROUPINFO("SYNAIRSPEED", 27, AP_TECS, _use_synthetic_airspeed, 0),
// @Param: OPTIONS
// @DisplayName: Extra TECS options
// @Description: This allows the enabling of special features in the speed/height controller
// @Bitmask: 0:GliderOnly
// @User: Advanced
AP_GROUPINFO("OPTIONS", 28, AP_TECS, _options, 0),
AP_GROUPEND
};
@ -1082,7 +1089,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
_detect_bad_descent();
// when soaring is active we never trigger a bad descent
if (soaring_active) {
if (soaring_active || (_options & OPTION_GLIDER_ONLY)) {
_flags.badDescent = false;
}

View File

@ -166,6 +166,11 @@ private:
AP_Int8 _pitch_min;
AP_Int8 _land_pitch_max;
AP_Float _maxSinkRate_approach;
AP_Int32 _options;
enum {
OPTION_GLIDER_ONLY=(1<<0),
};
// temporary _pitch_max_limit. Cleared on each loop. Clear when >= 90
int8_t _pitch_max_limit = 90;