mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ArduCopter: remove RTL_LAND parameter as it's been deprecated in favour of APPROACH_ALT.
Updated comments on ALT_HOLD_RTL and APPROACH_ALT to make it a little easier to understand.
This commit is contained in:
parent
71710b4514
commit
95c59fd4a4
@ -106,10 +106,9 @@ public:
|
||||
k_param_ch7_option,
|
||||
k_param_auto_slew_rate,
|
||||
k_param_sonar_type,
|
||||
k_param_super_simple,
|
||||
k_param_rtl_land_enabled, // Depricated!!
|
||||
k_param_axis_enabled,
|
||||
k_param_copter_leds_mode, //158
|
||||
k_param_super_simple = 155,
|
||||
k_param_axis_enabled = 157,
|
||||
k_param_copter_leds_mode,
|
||||
k_param_ahrs, // AHRS group
|
||||
|
||||
//
|
||||
@ -228,7 +227,6 @@ public:
|
||||
AP_Int8 optflow_enabled;
|
||||
AP_Float low_voltage;
|
||||
AP_Int8 super_simple;
|
||||
AP_Int8 rtl_land_enabled;
|
||||
AP_Int16 rtl_approach_alt;
|
||||
AP_Int8 tilt_comp;
|
||||
AP_Int8 axis_enabled;
|
||||
|
@ -28,8 +28,8 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(serial3_baud, "SERIAL3_BAUD", SERIAL3_BAUD/1000),
|
||||
|
||||
// @Param: ALT_HOLD_RTL
|
||||
// @DisplayName: Alt Hold RTL
|
||||
// @Description: This is the altitude the model will move to before Returning to Launch
|
||||
// @DisplayName: RTL Altitude
|
||||
// @Description: This is the altitude the model will move to before Returning to Launch. Set to zero to return at current altitude.
|
||||
// @Units: Meters
|
||||
// @Range: 0 400
|
||||
// @Increment: 1
|
||||
@ -89,17 +89,9 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
GSCALAR(super_simple, "SUPER_SIMPLE", SUPER_SIMPLE),
|
||||
|
||||
// @Param: RTL_LAND
|
||||
// @DisplayName: RTL Land
|
||||
// @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
|
||||
// @User: Standard
|
||||
// @ DEPRICATED
|
||||
GSCALAR(rtl_land_enabled, "RTL_LAND", 0),
|
||||
|
||||
// @Param: APPROACH_ALT
|
||||
// @DisplayName: Alt Hold RTL
|
||||
// @Description: This is the altitude the vehicle will move to before Returning to Launch
|
||||
// @DisplayName: RTL Approach Altitude
|
||||
// @Description: This is the altitude the vehicle will move to as the final stage of Returning to Launch. Set to zero to land.
|
||||
// @Units: Meters
|
||||
// @Range: 1 10
|
||||
// @Increment: .1
|
||||
|
Loading…
Reference in New Issue
Block a user