mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_TECS: set default pitch max to 15
This commit is contained in:
parent
7c57fb0c31
commit
60ec695f55
@ -140,7 +140,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = {
|
|||||||
// @Range: 0 45
|
// @Range: 0 45
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("PITCH_MAX", 15, AP_TECS, _pitch_max, 0),
|
AP_GROUPINFO("PITCH_MAX", 15, AP_TECS, _pitch_max, 15),
|
||||||
|
|
||||||
// @Param: PITCH_MIN
|
// @Param: PITCH_MIN
|
||||||
// @DisplayName: Minimum pitch in auto flight
|
// @DisplayName: Minimum pitch in auto flight
|
||||||
|
Loading…
Reference in New Issue
Block a user