From 7c849f1e52a10d9f6583fc8935bd6447a6a8f752 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Tue, 20 Dec 2016 15:20:15 -0500 Subject: [PATCH] Sub: Fixup parameter metadata --- ArduSub/Parameters.cpp | 20 ++++++++++---------- ArduSub/config.h | 4 ++-- ArduSub/defines.h | 4 +--- 3 files changed, 13 insertions(+), 15 deletions(-) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 8a739137e1..491924d65a 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -18,7 +18,7 @@ */ /* - * ArduCopter parameter definitions + * ArduSub parameter definitions * */ @@ -98,7 +98,7 @@ const AP_Param::Info Sub::var_info[] = { // @Param: RNGFND_GAIN // @DisplayName: Rangefinder gain - // @Description: Used to adjust the speed with which the target altitude is changed when objects are sensed below the copter + // @Description: Used to adjust the speed with which the target altitude is changed when objects are sensed below the sub // @Range: 0.01 2.0 // @Increment: 0.01 // @User: Standard @@ -107,13 +107,13 @@ const AP_Param::Info Sub::var_info[] = { // @Param: FS_BATT_ENABLE // @DisplayName: Battery Failsafe Enable // @Description: Controls whether failsafe will be invoked when battery voltage or current runs low - // @Values: 0:Disabled,1:Land,2:RTL + // @Values: 0:Disabled // @User: Standard GSCALAR(failsafe_battery_enabled, "FS_BATT_ENABLE", FS_BATT_DISABLED), // @Param: FS_BATT_VOLTAGE // @DisplayName: Failsafe battery voltage - // @Description: Battery voltage to trigger failsafe. Set to 0 to disable battery voltage failsafe. If the battery voltage drops below this voltage then the copter will RTL + // @Description: Battery voltage to trigger failsafe. Set to 0 to disable battery voltage failsafe. // @Units: Volts // @Increment: 0.1 // @User: Standard @@ -121,7 +121,7 @@ const AP_Param::Info Sub::var_info[] = { // @Param: FS_BATT_MAH // @DisplayName: Failsafe battery milliAmpHours - // @Description: Battery capacity remaining to trigger failsafe. Set to 0 to disable battery remaining failsafe. If the battery remaining drops below this level then the copter will RTL + // @Description: Battery capacity remaining to trigger failsafe. Set to 0 to disable battery remaining failsafe. // @Units: mAh // @Increment: 50 // @User: Standard @@ -283,7 +283,7 @@ const AP_Param::Info Sub::var_info[] = { // @Param: ESC_CALIBRATION // @DisplayName: ESC Calibration - // @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually. + // @Description: Controls whether ArduSub will enter ESC calibration on the next restart. Do not adjust this parameter manually. // @User: Advanced // @Values: 0:Normal Start-up, 1:Start-up in ESC Calibration mode if throttle high, 2:Start-up in ESC Calibration mode regardless of throttle, 9:Disabled GSCALAR(esc_calibrate, "ESC_CALIBRATION", 0), @@ -391,7 +391,7 @@ const AP_Param::Info Sub::var_info[] = { // @Param: FS_EKF_ACTION // @DisplayName: EKF Failsafe Action // @Description: Controls the action that will be taken when an EKF failsafe is invoked - // @Values: 1:Land, 2:AltHold, 3:Land even in Stabilize + // @Values: 1:Disabled // @User: Advanced GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT), @@ -405,7 +405,7 @@ const AP_Param::Info Sub::var_info[] = { // @Param: FS_CRASH_CHECK // @DisplayName: Crash check enable // @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected. - // @Values: 0:Disabled, 1:Enabled + // @Values: 0:Disabled // @User: Advanced GSCALAR(fs_crash_check, "FS_CRASH_CHECK", 0), @@ -508,7 +508,7 @@ const AP_Param::Info Sub::var_info[] = { // @Range: 0.5 4.0 GSCALAR(throttle_gain, "JS_THR_GAIN", 1.0f), - // @Param: CAM_TILT_CENTER + // @Param: CAM_CENTER // @DisplayName: Camera tilt mount center // @Description: Servo PWM at camera center position // @User: Standard @@ -597,7 +597,7 @@ const AP_Param::Info Sub::var_info[] = { // @Param: ACRO_YAW_P // @DisplayName: Acro Yaw P gain - // @Description: Converts pilot yaw input into a desired rate of rotation in ACRO, Stabilize and SPORT modes. Higher values mean faster rate of rotation. + // @Description: Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation. // @Range: 1 10 // @User: Standard GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P), diff --git a/ArduSub/config.h b/ArduSub/config.h index 52cafe8dec..cc3c2c5a7a 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -176,7 +176,7 @@ // Battery monitoring // #ifndef FS_BATT_VOLTAGE_DEFAULT - # define FS_BATT_VOLTAGE_DEFAULT 10.5f // default battery voltage below which failsafe will be triggered + # define FS_BATT_VOLTAGE_DEFAULT 0 // default battery voltage below which failsafe will be triggered #endif #ifndef FS_BATT_MAH_DEFAULT @@ -241,7 +241,7 @@ ////////////////////////////////////////////////////////////////////////////// // EKF Failsafe #ifndef FS_EKF_ACTION_DEFAULT - # define FS_EKF_ACTION_DEFAULT FS_EKF_ACTION_LAND // EKF failsafe triggers land by default + # define FS_EKF_ACTION_DEFAULT FS_EKF_ACTION_DISABLED // EKF failsafe triggers land by default #endif #ifndef FS_EKF_THRESHOLD_DEFAULT # define FS_EKF_THRESHOLD_DEFAULT 0.8f // EKF failsafe's default compass and velocity variance threshold above which the EKF failsafe will be triggered diff --git a/ArduSub/defines.h b/ArduSub/defines.h index f71786d4b7..3f5911e8a2 100644 --- a/ArduSub/defines.h +++ b/ArduSub/defines.h @@ -474,9 +474,7 @@ enum LoiterModeState { #define FS_TERRAIN_RECOVER_TIMEOUT_MS 10000 // EKF failsafe definitions (FS_EKF_ENABLE parameter) -#define FS_EKF_ACTION_LAND 1 // switch to LAND mode on EKF failsafe -#define FS_EKF_ACTION_ALTHOLD 2 // switch to ALTHOLD mode on EKF failsafe -#define FS_EKF_ACTION_LAND_EVEN_STABILIZE 3 // switch to Land mode on EKF failsafe even if in a manual flight mode like stabilize +#define FS_EKF_ACTION_DISABLED 1 // Disabled, not implemented yet in Sub // for mavlink SET_POSITION_TARGET messages #define MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ((1<<0) | (1<<1) | (1<<2))