mirror of https://github.com/ArduPilot/ardupilot
Parameters: Added new APPROACH_ALT params (g.rtl_approach_alt) which stored the users desired target altitude after RTL is complete.
This commit is contained in:
parent
0118208114
commit
f5e0b002ba
|
@ -100,8 +100,9 @@ public:
|
|||
k_param_sonar_type,
|
||||
k_param_super_simple,
|
||||
k_param_rtl_land_enabled,
|
||||
k_param_rtl_approach_alt,
|
||||
k_param_axis_enabled,
|
||||
k_param_copter_leds_mode, //158
|
||||
k_param_copter_leds_mode, //159
|
||||
|
||||
//
|
||||
// 160: Navigation parameters
|
||||
|
@ -210,6 +211,7 @@ public:
|
|||
AP_Float low_voltage;
|
||||
AP_Int8 super_simple;
|
||||
AP_Int8 rtl_land_enabled;
|
||||
AP_Uint8 rtl_approach_alt;
|
||||
AP_Int8 axis_enabled;
|
||||
AP_Int8 copter_leds_mode; // Operating mode of LED lighting system
|
||||
|
||||
|
@ -330,6 +332,7 @@ public:
|
|||
low_voltage (LOW_VOLTAGE),
|
||||
super_simple (SUPER_SIMPLE),
|
||||
rtl_land_enabled (RTL_AUTO_LAND),
|
||||
rtl_approach_alt (0),
|
||||
axis_enabled (AXIS_LOCK_ENABLED),
|
||||
copter_leds_mode (0),
|
||||
|
||||
|
|
|
@ -33,6 +33,7 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
|||
GSCALAR(low_voltage, "LOW_VOLT"),
|
||||
GSCALAR(super_simple, "SUPER_SIMPLE"),
|
||||
GSCALAR(rtl_land_enabled, "RTL_LAND"),
|
||||
GSCALAR(rtl_approach_alt, "APPROACH_ALT"),
|
||||
|
||||
|
||||
GSCALAR(waypoint_mode, "WP_MODE"),
|
||||
|
|
Loading…
Reference in New Issue