mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Sub: Remove unused WP_NAVALT_MIN parameter
This commit is contained in:
parent
b4260c77be
commit
fab139ecce
@ -768,13 +768,6 @@ const AP_Param::Info Sub::var_info[] = {
|
|||||||
*/
|
*/
|
||||||
const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||||
|
|
||||||
// @Param: WP_NAVALT_MIN
|
|
||||||
// @DisplayName: Minimum navigation altitude
|
|
||||||
// @Description: This is the altitude in meters above which for navigation can begin. This applies in auto takeoff and auto landing.
|
|
||||||
// @Range: 0 5
|
|
||||||
// @User: Standard
|
|
||||||
AP_GROUPINFO("WP_NAVALT_MIN", 1, ParametersG2, wp_navalt_min, 0),
|
|
||||||
|
|
||||||
#if PROXIMITY_ENABLED == ENABLED
|
#if PROXIMITY_ENABLED == ENABLED
|
||||||
// @Group: PRX
|
// @Group: PRX
|
||||||
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
|
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
|
||||||
|
@ -368,9 +368,6 @@ public:
|
|||||||
// var_info for holding Parameter information
|
// var_info for holding Parameter information
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
// altitude at which nav control can start in takeoff
|
|
||||||
AP_Float wp_navalt_min;
|
|
||||||
|
|
||||||
#if GRIPPER_ENABLED
|
#if GRIPPER_ENABLED
|
||||||
AP_Gripper gripper;
|
AP_Gripper gripper;
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user