mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_TECS: added set_pitch_max_limit() API
This commit is contained in:
parent
acb4885989
commit
4f9927beda
@ -828,6 +828,11 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
|||||||
} else {
|
} else {
|
||||||
_PITCHmaxf = MIN(_pitch_max, aparm.pitch_limit_max_cd * 0.01f);
|
_PITCHmaxf = MIN(_pitch_max, aparm.pitch_limit_max_cd * 0.01f);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// apply temporary pitch limit and clear
|
||||||
|
_PITCHmaxf = constrain_float(_PITCHmaxf, -90, _pitch_max_limit);
|
||||||
|
_pitch_max_limit = 90;
|
||||||
|
|
||||||
if (_pitch_min >= 0) {
|
if (_pitch_min >= 0) {
|
||||||
_PITCHminf = aparm.pitch_limit_min_cd * 0.01f;
|
_PITCHminf = aparm.pitch_limit_min_cd * 0.01f;
|
||||||
} else {
|
} else {
|
||||||
|
@ -97,6 +97,11 @@ public:
|
|||||||
_path_proportion = constrain_float(path_proportion, 0.0f, 1.0f);
|
_path_proportion = constrain_float(path_proportion, 0.0f, 1.0f);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// set pitch max limit in degrees
|
||||||
|
void set_pitch_max_limit(int8_t pitch_limit) {
|
||||||
|
_pitch_max_limit = pitch_limit;
|
||||||
|
}
|
||||||
|
|
||||||
// this supports the TECS_* user settable parameters
|
// this supports the TECS_* user settable parameters
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
@ -155,6 +160,9 @@ private:
|
|||||||
AP_Int8 _pitch_min;
|
AP_Int8 _pitch_min;
|
||||||
AP_Int8 _land_pitch_max;
|
AP_Int8 _land_pitch_max;
|
||||||
|
|
||||||
|
// temporary _pitch_max_limit. Cleared on each loop. Clear when >= 90
|
||||||
|
int8_t _pitch_max_limit = 90;
|
||||||
|
|
||||||
// current height estimate (above field elevation)
|
// current height estimate (above field elevation)
|
||||||
float _height;
|
float _height;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user