mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
SRV_Channels: rename SERVO_DEF_RATE to SERVO_RATE
This commit is contained in:
parent
687ec98e5d
commit
298eaaeb3e
@ -103,13 +103,13 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO_FRAME("_AUTO_TRIM", 17, SRV_Channels, auto_trim, 0, AP_PARAM_FRAME_PLANE),
|
AP_GROUPINFO_FRAME("_AUTO_TRIM", 17, SRV_Channels, auto_trim, 0, AP_PARAM_FRAME_PLANE),
|
||||||
|
|
||||||
// @Param: _DEF_RATE
|
// @Param: _RATE
|
||||||
// @DisplayName: Default output rate
|
// @DisplayName: Servo default output rate
|
||||||
// @Description: This sets the default output rate in Hz for all outputs.
|
// @Description: This sets the default output rate in Hz for all outputs.
|
||||||
// @Range: 25 400
|
// @Range: 25 400
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
AP_GROUPINFO("_DEF_RATE", 18, SRV_Channels, default_rate, 50),
|
AP_GROUPINFO("_RATE", 18, SRV_Channels, default_rate, 50),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user