mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_TECS: change param TECS_LAND_SPDWGT default from +1 to -1
This commit is contained in:
parent
358dcd56e8
commit
a0755a84e7
@ -134,7 +134,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = {
|
|||||||
// @Range: -1.0 2.0
|
// @Range: -1.0 2.0
|
||||||
// @Increment: 0.1
|
// @Increment: 0.1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("LAND_SPDWGT", 14, AP_TECS, _spdWeightLand, 1.0f),
|
AP_GROUPINFO("LAND_SPDWGT", 14, AP_TECS, _spdWeightLand, -1.0f),
|
||||||
|
|
||||||
// @Param: PITCH_MAX
|
// @Param: PITCH_MAX
|
||||||
// @DisplayName: Maximum pitch in auto flight
|
// @DisplayName: Maximum pitch in auto flight
|
||||||
|
Loading…
Reference in New Issue
Block a user