mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Parameters
removed unused parameters for retro loiter
This commit is contained in:
parent
42a321b76c
commit
44e12c6d2d
@ -112,7 +112,6 @@ public:
|
||||
k_param_crosstrack_gain,
|
||||
k_param_auto_land_timeout,
|
||||
k_param_rtl_approach_alt,
|
||||
k_param_retro_loiter,
|
||||
|
||||
|
||||
//
|
||||
@ -215,7 +214,6 @@ public:
|
||||
AP_Int8 super_simple;
|
||||
AP_Int8 rtl_land_enabled;
|
||||
AP_Float rtl_approach_alt;
|
||||
AP_Int8 retro_loiter;
|
||||
AP_Int8 axis_enabled;
|
||||
AP_Int8 copter_leds_mode; // Operating mode of LED lighting system
|
||||
|
||||
@ -337,7 +335,6 @@ public:
|
||||
super_simple (SUPER_SIMPLE),
|
||||
rtl_land_enabled (RTL_AUTO_LAND),
|
||||
rtl_approach_alt (0.0),
|
||||
retro_loiter (RETRO_LOITER_MODE),
|
||||
axis_enabled (AXIS_LOCK_ENABLED),
|
||||
copter_leds_mode (9),
|
||||
|
||||
|
@ -94,13 +94,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
GSCALAR(rtl_approach_alt, "APPROACH_ALT"),
|
||||
|
||||
// @Param: RETRO_LOITER
|
||||
// @DisplayName: Retro Loiter
|
||||
// @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
|
||||
// @User: Standard
|
||||
GSCALAR(retro_loiter, "RETRO_LOITER"),
|
||||
|
||||
GSCALAR(waypoint_mode, "WP_MODE"),
|
||||
GSCALAR(command_total, "WP_TOTAL"),
|
||||
GSCALAR(command_index, "WP_INDEX"),
|
||||
|
Loading…
Reference in New Issue
Block a user