mirror of https://github.com/ArduPilot/ardupilot
Parameters.pde/AP_MotorsHeli: Updated comments to leverage the new value aliases
This commit is contained in:
parent
2a85a64b6e
commit
292f9699fa
|
@ -32,7 +32,7 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||||
|
|
||||||
// @Param: SONAR_ENABLE
|
// @Param: SONAR_ENABLE
|
||||||
// @DisplayName: Enable Sonar
|
// @DisplayName: Enable Sonar
|
||||||
// @Description: Setting this to true (1) will enable the sonar. Setting this to false(0) will disable the sonar
|
// @Description: Setting this to Enabled(1) will enable the sonar. Setting this to Disabled(0) will disable the sonar
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(sonar_enabled, "SONAR_ENABLE"),
|
GSCALAR(sonar_enabled, "SONAR_ENABLE"),
|
||||||
|
@ -51,14 +51,14 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||||
|
|
||||||
// @Param: MAG_ENABLE
|
// @Param: MAG_ENABLE
|
||||||
// @DisplayName: Enable Compass
|
// @DisplayName: Enable Compass
|
||||||
// @Description: Setting this to true (1) will enable the compass. Setting this to false(0) will disable the compass
|
// @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(compass_enabled, "MAG_ENABLE"),
|
GSCALAR(compass_enabled, "MAG_ENABLE"),
|
||||||
|
|
||||||
// @Param: FLOW_ENABLE
|
// @Param: FLOW_ENABLE
|
||||||
// @DisplayName: Enable Optical Flow
|
// @DisplayName: Enable Optical Flow
|
||||||
// @Description: Setting this to true (1) will enable optical flow. Setting this to false(0) will disable optical flow
|
// @Description: Setting this to Enabled(1) will enable optical flow. Setting this to Disabled(0) will disable optical flow
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(optflow_enabled, "FLOW_ENABLE"),
|
GSCALAR(optflow_enabled, "FLOW_ENABLE"),
|
||||||
|
@ -73,14 +73,14 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||||
|
|
||||||
// @Param: SUPER_SIMPLE
|
// @Param: SUPER_SIMPLE
|
||||||
// @DisplayName: Enable Super Simple Mode
|
// @DisplayName: Enable Super Simple Mode
|
||||||
// @Description: Setting this to true (1) will enable Super Simple Mode. Setting this to false(0) will disable Super Simple Mode
|
// @Description: Setting this to Enabled(1) will enable Super Simple Mode. Setting this to Disabled(0) will disable Super Simple Mode
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(super_simple, "SUPER_SIMPLE"),
|
GSCALAR(super_simple, "SUPER_SIMPLE"),
|
||||||
|
|
||||||
// @Param: RTL_LAND
|
// @Param: RTL_LAND
|
||||||
// @DisplayName: RTL Land
|
// @DisplayName: RTL Land
|
||||||
// @Description: Setting this to true (1) will enable landing after RTL. Setting this to false(0) will disable landing after RTL.
|
// @Description: Setting this to Enabled(1) will enable landing after RTL. Setting this to Disabled(0) will disable landing after RTL.
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(rtl_land_enabled, "RTL_LAND"),
|
GSCALAR(rtl_land_enabled, "RTL_LAND"),
|
||||||
|
@ -96,7 +96,7 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||||
|
|
||||||
// @Param: RETRO_LOITER
|
// @Param: RETRO_LOITER
|
||||||
// @DisplayName: Retro Loiter
|
// @DisplayName: Retro Loiter
|
||||||
// @Description: Setting this to true (1) will enable the Loiter from 2.0.49. Setting this to false(0) will use the most recent Loiter routines.
|
// @Description: Setting this to Enabled(1) will enable the Loiter from 2.0.49. Setting this to Disabled(0) will use the most recent Loiter routines.
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(retro_loiter, "RETRO_LOITER"),
|
GSCALAR(retro_loiter, "RETRO_LOITER"),
|
||||||
|
|
|
@ -87,7 +87,8 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
||||||
|
|
||||||
// @Param: GYR_ENABLE
|
// @Param: GYR_ENABLE
|
||||||
// @DisplayName: External Gyro Enabled
|
// @DisplayName: External Gyro Enabled
|
||||||
// @Description: Setting this to true (1) will enable an external rudder gyro control. Setting this to false(0) will disable the external gyro control and will revert to internal rudder control.
|
// @Description: Setting this to Enabled(1) will enable an external rudder gyro control. Setting this to Disabled(0) will disable the external gyro control and will revert to internal rudder control.
|
||||||
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("GYR_ENABLE", 9, AP_MotorsHeli, ext_gyro_enabled),
|
AP_GROUPINFO("GYR_ENABLE", 9, AP_MotorsHeli, ext_gyro_enabled),
|
||||||
|
|
||||||
|
@ -108,7 +109,8 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
||||||
|
|
||||||
// @Param: SV_MAN
|
// @Param: SV_MAN
|
||||||
// @DisplayName: Manual Servo Mode
|
// @DisplayName: Manual Servo Mode
|
||||||
// @Description: Setting this to true (1) will pass radio inputs directly to servos. Setting this to false(0) will enable Arducopter control of servos.
|
// @Description: Setting this to Enabled(1) will pass radio inputs directly to servos. Setting this to Disabled(0) will enable Arducopter control of servos.
|
||||||
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("SV_MAN", 12, AP_MotorsHeli, servo_manual),
|
AP_GROUPINFO("SV_MAN", 12, AP_MotorsHeli, servo_manual),
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue