mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: fix flowhold param description
This commit is contained in:
parent
192244bb6d
commit
e51d842ca5
@ -30,6 +30,13 @@ const AP_Param::GroupInfo Copter::ModeFlowHold::var_info[] = {
|
|||||||
// @Increment: 10
|
// @Increment: 10
|
||||||
// @Units: cdeg
|
// @Units: cdeg
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
|
// @Param: _XY_FILT_HZ
|
||||||
|
// @DisplayName: FlowHold filter on input to control
|
||||||
|
// @Description: FlowHold (horizontal) filter on input to control
|
||||||
|
// @Range: 0 100
|
||||||
|
// @Units: Hz
|
||||||
|
// @User: Advanced
|
||||||
AP_SUBGROUPINFO(flow_pi_xy, "_XY_", 1, Copter::ModeFlowHold, AC_PI_2D),
|
AP_SUBGROUPINFO(flow_pi_xy, "_XY_", 1, Copter::ModeFlowHold, AC_PI_2D),
|
||||||
|
|
||||||
// @Param: _FLOW_MAX
|
// @Param: _FLOW_MAX
|
||||||
|
Loading…
Reference in New Issue
Block a user