From 298eaaeb3e55780088992aad3f86de94b7535502 Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Tue, 25 Jul 2017 12:15:00 +0900 Subject: [PATCH] SRV_Channels: rename SERVO_DEF_RATE to SERVO_RATE --- libraries/SRV_Channel/SRV_Channels.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channels.cpp b/libraries/SRV_Channel/SRV_Channels.cpp index fdc96a646e..6a328e85e6 100644 --- a/libraries/SRV_Channel/SRV_Channels.cpp +++ b/libraries/SRV_Channel/SRV_Channels.cpp @@ -103,13 +103,13 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = { // @User: Advanced AP_GROUPINFO_FRAME("_AUTO_TRIM", 17, SRV_Channels, auto_trim, 0, AP_PARAM_FRAME_PLANE), - // @Param: _DEF_RATE - // @DisplayName: Default output rate - // @Description: This sets the default output rate in Hz for all outputs. + // @Param: _RATE + // @DisplayName: Servo default output rate + // @Description: This sets the default output rate in Hz for all outputs. // @Range: 25 400 // @User: Advanced // @Units: Hz - AP_GROUPINFO("_DEF_RATE", 18, SRV_Channels, default_rate, 50), + AP_GROUPINFO("_RATE", 18, SRV_Channels, default_rate, 50), AP_GROUPEND };