From fb9793cb7a7ab6573750fee856ce347846fe34cb Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Tue, 17 Mar 2026 21:55:35 -0800 Subject: [PATCH] refactor(navigator): convert params.c to module.yaml Convert 6 parameter file(s) from legacy C format to YAML module configuration. --- src/modules/navigator/CMakeLists.txt | 7 + src/modules/navigator/geofence_params.c | 119 ---------- src/modules/navigator/geofence_params.yaml | 70 ++++++ src/modules/navigator/mission_params.c | 164 -------------- src/modules/navigator/mission_params.yaml | 115 ++++++++++ src/modules/navigator/navigator_params.c | 210 ------------------ src/modules/navigator/navigator_params.yaml | 142 ++++++++++++ src/modules/navigator/precland_params.c | 121 ---------- src/modules/navigator/precland_params.yaml | 72 ++++++ src/modules/navigator/rtl_params.c | 203 ----------------- src/modules/navigator/rtl_params.yaml | 152 +++++++++++++ src/modules/navigator/vtol_takeoff_params.c | 53 ----- .../navigator/vtol_takeoff_params.yaml | 15 ++ 13 files changed, 573 insertions(+), 870 deletions(-) delete mode 100644 src/modules/navigator/geofence_params.c create mode 100644 src/modules/navigator/geofence_params.yaml delete mode 100644 src/modules/navigator/mission_params.c create mode 100644 src/modules/navigator/mission_params.yaml delete mode 100644 src/modules/navigator/navigator_params.c create mode 100644 src/modules/navigator/navigator_params.yaml delete mode 100644 src/modules/navigator/precland_params.c create mode 100644 src/modules/navigator/precland_params.yaml delete mode 100644 src/modules/navigator/rtl_params.c create mode 100644 src/modules/navigator/rtl_params.yaml delete mode 100644 src/modules/navigator/vtol_takeoff_params.c create mode 100644 src/modules/navigator/vtol_takeoff_params.yaml diff --git a/src/modules/navigator/CMakeLists.txt b/src/modules/navigator/CMakeLists.txt index c55cae3f07..743fdfa96c 100644 --- a/src/modules/navigator/CMakeLists.txt +++ b/src/modules/navigator/CMakeLists.txt @@ -62,6 +62,13 @@ px4_add_module( MODULE modules__navigator MAIN navigator SRCS ${NAVIGATOR_SOURCES} + MODULE_CONFIG + geofence_params.yaml + mission_params.yaml + navigator_params.yaml + precland_params.yaml + rtl_params.yaml + vtol_takeoff_params.yaml DEPENDS dataman_client geo diff --git a/src/modules/navigator/geofence_params.c b/src/modules/navigator/geofence_params.c deleted file mode 100644 index a775405282..0000000000 --- a/src/modules/navigator/geofence_params.c +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file geofence_params.c - * - * Parameters for geofence - * - * @author Thomas Gubler - */ - -/* - * Geofence parameters, accessible via MAVLink - */ - -/** - * Geofence violation action. - * - * Note: Setting this value to 4 enables flight termination, - * which will kill the vehicle on violation of the fence. - * - * @min 0 - * @max 5 - * @value 0 None - * @value 1 Warning - * @value 2 Hold mode - * @value 3 Return mode - * @value 4 Terminate - * @value 5 Land mode - * @group Geofence - */ -PARAM_DEFINE_INT32(GF_ACTION, 2); - -/** - * Geofence source - * - * Select which position source should be used. Selecting GPS instead of global position makes sure that there is - * no dependence on the position estimator - * 0 = global position, 1 = GPS - * - * @min 0 - * @max 1 - * @value 0 GPOS - * @value 1 GPS - * @group Geofence - */ -PARAM_DEFINE_INT32(GF_SOURCE, 0); - -/** - * Max horizontal distance from Home - * - * Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action. - * Disabled if 0. - * - * @unit m - * @min 0 - * @max 10000 - * @increment 1 - * @group Geofence - */ -PARAM_DEFINE_FLOAT(GF_MAX_HOR_DIST, 0.0f); - -/** - * Max vertical distance from Home - * - * Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action. - * Disabled if 0. - * - * @unit m - * @min 0 - * @max 10000 - * @increment 1 - * @group Geofence - */ -PARAM_DEFINE_FLOAT(GF_MAX_VER_DIST, 0.0f); - -/** - * [EXPERIMENTAL] Use Pre-emptive geofence triggering - * - * WARNING: This experimental feature may cause flyaways. Use at your own risk. - * - * Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory - * would result in a breach happening before the vehicle can make evasive maneuvers. - * The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). - * - * @boolean - * @group Geofence - */ -PARAM_DEFINE_INT32(GF_PREDICT, 0); diff --git a/src/modules/navigator/geofence_params.yaml b/src/modules/navigator/geofence_params.yaml new file mode 100644 index 0000000000..dc0c57301b --- /dev/null +++ b/src/modules/navigator/geofence_params.yaml @@ -0,0 +1,70 @@ +module_name: navigator +parameters: +- group: Geofence + definitions: + GF_ACTION: + description: + short: Geofence violation action + long: |- + Note: Setting this value to 4 enables flight termination, + which will kill the vehicle on violation of the fence. + type: enum + values: + 0: None + 1: Warning + 2: Hold mode + 3: Return mode + 4: Terminate + 5: Land mode + default: 2 + min: 0 + max: 5 + GF_SOURCE: + description: + short: Geofence source + long: |- + Select which position source should be used. Selecting GPS instead of global position makes sure that there is + no dependence on the position estimator + 0 = global position, 1 = GPS + type: enum + values: + 0: GPOS + 1: GPS + default: 0 + min: 0 + max: 1 + GF_MAX_HOR_DIST: + description: + short: Max horizontal distance from Home + long: |- + Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action. + Disabled if 0. + type: float + default: 0.0 + unit: m + min: 0 + max: 10000 + increment: 1 + GF_MAX_VER_DIST: + description: + short: Max vertical distance from Home + long: |- + Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action. + Disabled if 0. + type: float + default: 0.0 + unit: m + min: 0 + max: 10000 + increment: 1 + GF_PREDICT: + description: + short: '[EXPERIMENTAL] Use Pre-emptive geofence triggering' + long: |- + WARNING: This experimental feature may cause flyaways. Use at your own risk. + + Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory + would result in a breach happening before the vehicle can make evasive maneuvers. + The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). + type: boolean + default: 0 diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c deleted file mode 100644 index c0bbf5c254..0000000000 --- a/src/modules/navigator/mission_params.c +++ /dev/null @@ -1,164 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mission_params.c - * - * Parameters for mission. - * - * @author Julian Oes - */ - -/* - * Mission parameters, accessible via MAVLink - */ - -/** - * Default take-off altitude - * - * This is the relative altitude the system will take off to - * if not otherwise specified. - * - * @unit m - * @min 0 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_TAKEOFF_ALT, 2.5f); - -/** - * Mission takeoff/landing required - * - * Specifies if a mission has to contain a takeoff and/or mission landing. - * Validity of configured takeoffs/landings is checked independently of the setting here. - * - * @value 0 No requirements - * @value 1 Require a takeoff - * @value 2 Require a landing - * @value 3 Require a takeoff and a landing - * @value 4 Require both a takeoff and a landing, or neither - * @value 5 Same as previous when landed, in-air require landing only if no valid VTOL approach is present - * @group Mission - */ -PARAM_DEFINE_INT32(MIS_TKO_LAND_REQ, 0); - -/** - * Maximal horizontal distance from Home to first waypoint - * - * There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home. - * Has no effect on mission validity. - * Set a value of zero or less to disable. - * - * @unit m - * @min -1 - * @max 100000 - * @decimal 1 - * @increment 100 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 10000); - -/** -* Enable yaw control of the mount. (Only affects multicopters and ROI mission items) -* -* If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. -* If disabled, the vehicle will yaw towards the ROI. -* -* @value 0 Disable -* @value 1 Enable -* @min 0 -* @max 1 -* @group Mission -*/ -PARAM_DEFINE_INT32(MIS_MNT_YAW_CTL, 0); - -/** - * Time in seconds we wait on reaching target heading at a waypoint if it is forced. - * - * If set > 0 it will ignore the target heading for normal waypoint acceptance. If the - * waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. - * Mainly useful for VTOLs that have less yaw authority and might not reach target - * yaw in wind. Disabled by default. - * - * @unit s - * @min -1 - * @max 20 - * @decimal 1 - * @increment 1 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_YAW_TMT, -1.0f); - -/** - * Max yaw error in degrees needed for waypoint heading acceptance. - * - * @unit deg - * @min 0 - * @max 90 - * @decimal 1 - * @increment 1 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_YAW_ERR, 12.0f); - -/** - * Landing abort min altitude - * - * Minimum altitude above landing point that the vehicle will climb to after an aborted landing. - * Then vehicle will loiter in this altitude until further command is received. - * Only applies to fixed-wing vehicles. - * - * @unit m - * @min 0 - * @group Mission - */ -PARAM_DEFINE_INT32(MIS_LND_ABRT_ALT, 30); - -/** - * Timeout to allow the payload to execute the mission command - * - * Ensure: - * gripper: NAV_CMD_DO_GRIPPER - * has released before continuing mission. - * winch: CMD_DO_WINCH - * has delivered before continuing mission. - * gimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW - * has reached the commanded orientation before beginning to take pictures. - * - * @unit s - * @min 0 - * @decimal 1 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_COMMAND_TOUT, 0.f); diff --git a/src/modules/navigator/mission_params.yaml b/src/modules/navigator/mission_params.yaml new file mode 100644 index 0000000000..8766663168 --- /dev/null +++ b/src/modules/navigator/mission_params.yaml @@ -0,0 +1,115 @@ +module_name: navigator +parameters: +- group: Mission + definitions: + MIS_TAKEOFF_ALT: + description: + short: Default take-off altitude + long: |- + This is the relative altitude the system will take off to + if not otherwise specified. + type: float + default: 2.5 + unit: m + min: 0 + decimal: 1 + increment: 0.5 + MIS_TKO_LAND_REQ: + description: + short: Mission takeoff/landing required + long: |- + Specifies if a mission has to contain a takeoff and/or mission landing. + Validity of configured takeoffs/landings is checked independently of the setting here. + type: enum + values: + 0: No requirements + 1: Require a takeoff + 2: Require a landing + 3: Require a takeoff and a landing + 4: Require both a takeoff and a landing, or neither + 5: Same as previous when landed, in-air require landing only if no valid VTOL + approach is present + default: 0 + MIS_DIST_1WP: + description: + short: Maximal horizontal distance from Home to first waypoint + long: |- + There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home. + Has no effect on mission validity. + Set a value of zero or less to disable. + type: float + default: 10000 + unit: m + min: -1 + max: 100000 + decimal: 1 + increment: 100 + MIS_MNT_YAW_CTL: + description: + short: Enable gimbal yaw control in missions + long: |- + Enable yaw control of the mount. (Only affects multicopters and ROI mission items) + + If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. + If disabled, the vehicle will yaw towards the ROI. + type: enum + values: + 0: Disable + 1: Enable + default: 0 + min: 0 + max: 1 + MIS_YAW_TMT: + description: + short: Waypoint heading timeout + long: |- + Time in seconds we wait on reaching target heading at a waypoint if it is forced + + If set > 0 it will ignore the target heading for normal waypoint acceptance. If the + waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. + Mainly useful for VTOLs that have less yaw authority and might not reach target + yaw in wind. Disabled by default. + type: float + default: -1.0 + unit: s + min: -1 + max: 20 + decimal: 1 + increment: 1 + MIS_YAW_ERR: + description: + short: Max yaw error in degrees needed for waypoint heading acceptance + type: float + default: 12.0 + unit: deg + min: 0 + max: 90 + decimal: 1 + increment: 1 + MIS_LND_ABRT_ALT: + description: + short: Landing abort min altitude + long: |- + Minimum altitude above landing point that the vehicle will climb to after an aborted landing. + Then vehicle will loiter in this altitude until further command is received. + Only applies to fixed-wing vehicles. + type: int32 + default: 30 + unit: m + min: 0 + MIS_COMMAND_TOUT: + description: + short: Timeout to allow the payload to execute the mission command + long: |- + Ensure: + gripper: NAV_CMD_DO_GRIPPER + has released before continuing mission. + winch: CMD_DO_WINCH + has delivered before continuing mission. + gimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW + has reached the commanded orientation before beginning to take pictures. + type: float + default: 0.0 + unit: s + min: 0 + decimal: 1 diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c deleted file mode 100644 index f830011c20..0000000000 --- a/src/modules/navigator/navigator_params.c +++ /dev/null @@ -1,210 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file navigator_params.c - * - * Parameters for navigator in general - * - * @author Julian Oes - * @author Thomas Gubler - */ - -/** - * Loiter radius (FW only) - * - * Default value of loiter radius in fixed-wing mode (e.g. for Loiter mode). - * - * The direction of the loiter can be set via the sign: A positive value for - * clockwise, negative for counter-clockwise. - * - * @unit m - * @min -10000 - * @max 10000 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 80.0f); - -/** - * Acceptance Radius - * - * Default acceptance radius, overridden by acceptance radius of waypoint if set. - * For fixed wing the npfg switch distance is used for horizontal acceptance. - * - * @unit m - * @min 0.05 - * @max 200.0 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 10.0f); - -/** - * FW Altitude Acceptance Radius - * - * Acceptance radius for fixedwing altitude. - * - * @unit m - * @min 0.05 - * @max 200.0 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_FW_ALT_RAD, 10.0f); - -/** - * FW Altitude Acceptance Radius before a landing - * - * Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller - * than the standard vertical acceptance because close to the ground higher accuracy is required. - * - * @unit m - * @min 0.05 - * @max 200.0 - * @decimal 1 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_FW_ALTL_RAD, 5.0f); - -/** - * MC Altitude Acceptance Radius - * - * Acceptance radius for multicopter altitude. - * - * @unit m - * @min 0.05 - * @max 200.0 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_MC_ALT_RAD, 0.8f); - -/** - * Set traffic avoidance mode - * - * Enabling this will allow the system to respond - * to transponder data from e.g. ADSB transponders - * - * @value 0 Disabled - * @value 1 Warn only - * @value 2 Return mode - * @value 3 Land mode - * @value 4 Position Hold mode - * - * @group Mission - */ -PARAM_DEFINE_INT32(NAV_TRAFF_AVOID, 1); - -/** - * Set NAV TRAFFIC AVOID horizontal distance - * - * Defines a crosstrack horizontal distance - * - * @unit m - * @min 500 - * - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_TRAFF_A_HOR, 500); - -/** - * Set NAV TRAFFIC AVOID vertical distance - * - * - * @unit m - * @min 10 - * @max 500 - * - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_TRAFF_A_VER, 500); - -/** - * Estimated time until collision - * - * Minimum acceptable time until collsion. - * Assumes constant speed over 3d distance. - * - * @unit s - * @min 1 - * @max 900000000 - * @group Mission - */ -PARAM_DEFINE_INT32(NAV_TRAFF_COLL_T, 60); - -/** - * Force VTOL mode takeoff and land - * - * @boolean - * @group Mission - */ -PARAM_DEFINE_INT32(NAV_FORCE_VT, 1); - -/** - * Minimum Loiter altitude - * - * This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this - * mode without specifying an altitude (e.g. through Loiter switch on RC). - * Doesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint ("Go to"). - * Set to a negative value to disable. - * - * @unit m - * @min -1 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_MIN_LTR_ALT, -1.f); - -/** - * Minimum height above ground during Mission and RTL - * - * Minimum height above ground the vehicle is allowed to descend to during Mission and RTL, - * excluding landing commands. - * Requires a distance sensor to be set up. - * Note: only prevents the vehicle from descending further, but does not force it to climb. - * - * Set to a negative value to disable. - * - * @unit m - * @min -1 - * @decimal 1 - * @increment 1 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_MIN_GND_DIST, -1.f); diff --git a/src/modules/navigator/navigator_params.yaml b/src/modules/navigator/navigator_params.yaml new file mode 100644 index 0000000000..ed7325de58 --- /dev/null +++ b/src/modules/navigator/navigator_params.yaml @@ -0,0 +1,142 @@ +module_name: navigator +parameters: +- group: Mission + definitions: + NAV_LOITER_RAD: + description: + short: Loiter radius (FW only) + long: |- + Default value of loiter radius in fixed-wing mode (e.g. for Loiter mode). + + The direction of the loiter can be set via the sign: A positive value for + clockwise, negative for counter-clockwise. + type: float + default: 80.0 + unit: m + min: -10000 + max: 10000 + decimal: 1 + increment: 0.5 + NAV_ACC_RAD: + description: + short: Acceptance Radius + long: |- + Default acceptance radius, overridden by acceptance radius of waypoint if set. + For fixed wing the npfg switch distance is used for horizontal acceptance. + type: float + default: 10.0 + unit: m + min: 0.05 + max: 200.0 + decimal: 1 + increment: 0.5 + NAV_FW_ALT_RAD: + description: + short: FW Altitude Acceptance Radius + long: Acceptance radius for fixedwing altitude. + type: float + default: 10.0 + unit: m + min: 0.05 + max: 200.0 + decimal: 1 + increment: 0.5 + NAV_FW_ALTL_RAD: + description: + short: FW Altitude Acceptance Radius before a landing + long: |- + Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller + than the standard vertical acceptance because close to the ground higher accuracy is required. + type: float + default: 5.0 + unit: m + min: 0.05 + max: 200.0 + decimal: 1 + NAV_MC_ALT_RAD: + description: + short: MC Altitude Acceptance Radius + long: Acceptance radius for multicopter altitude. + type: float + default: 0.8 + unit: m + min: 0.05 + max: 200.0 + decimal: 1 + increment: 0.5 + NAV_TRAFF_AVOID: + description: + short: Set traffic avoidance mode + long: |- + Enabling this will allow the system to respond + to transponder data from e.g. ADSB transponders + type: enum + values: + 0: Disabled + 1: Warn only + 2: Return mode + 3: Land mode + 4: Position Hold mode + default: 1 + NAV_TRAFF_A_HOR: + description: + short: Set NAV TRAFFIC AVOID horizontal distance + long: Defines a crosstrack horizontal distance + type: float + default: 500 + unit: m + min: 500 + NAV_TRAFF_A_VER: + description: + short: Set NAV TRAFFIC AVOID vertical distance + type: float + default: 500 + unit: m + min: 10 + max: 500 + NAV_TRAFF_COLL_T: + description: + short: Estimated time until collision + long: |- + Minimum acceptable time until collsion. + Assumes constant speed over 3d distance. + type: int32 + default: 60 + unit: s + min: 1 + max: 900000000 + NAV_FORCE_VT: + description: + short: Force VTOL mode takeoff and land + type: boolean + default: 1 + NAV_MIN_LTR_ALT: + description: + short: Minimum Loiter altitude + long: |- + This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this + mode without specifying an altitude (e.g. through Loiter switch on RC). + Doesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint ("Go to"). + Set to a negative value to disable. + type: float + default: -1.0 + unit: m + min: -1 + decimal: 1 + increment: 0.5 + NAV_MIN_GND_DIST: + description: + short: Minimum height above ground during Mission and RTL + long: |- + Minimum height above ground the vehicle is allowed to descend to during Mission and RTL, + excluding landing commands. + Requires a distance sensor to be set up. + Note: only prevents the vehicle from descending further, but does not force it to climb. + + Set to a negative value to disable. + type: float + default: -1.0 + unit: m + min: -1 + decimal: 1 + increment: 1 diff --git a/src/modules/navigator/precland_params.c b/src/modules/navigator/precland_params.c deleted file mode 100644 index 9c2e63ac32..0000000000 --- a/src/modules/navigator/precland_params.c +++ /dev/null @@ -1,121 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file precland_params.c - * - * Parameters for precision landing. - * - * @author Nicolas de Palezieux (Sunflower Labs) - */ - -/** - * Landing Target Timeout - * - * Time after which the landing target is considered lost without any new measurements. - * - * @unit s - * @min 0.0 - * @max 50 - * @decimal 1 - * @increment 0.5 - * @group Precision Land - */ -PARAM_DEFINE_FLOAT(PLD_BTOUT, 5.0f); - -/** - * Horizontal acceptance radius - * - * Start descending if closer above landing target than this. - * - * @unit m - * @min 0.0 - * @max 10 - * @decimal 2 - * @increment 0.1 - * @group Precision Land - */ -PARAM_DEFINE_FLOAT(PLD_HACC_RAD, 0.2f); - -/** - * Final approach altitude - * - * Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground. - * - * @unit m - * @min 0.0 - * @max 10 - * @decimal 2 - * @increment 0.1 - * @group Precision Land - */ -PARAM_DEFINE_FLOAT(PLD_FAPPR_ALT, 0.1f); - -/** - * Search altitude - * - * Altitude above home to which to climb when searching for the landing target. - * - * @unit m - * @min 0.0 - * @max 100 - * @decimal 1 - * @increment 0.1 - * @group Precision Land - */ -PARAM_DEFINE_FLOAT(PLD_SRCH_ALT, 10.0f); - -/** - * Search timeout - * - * Time allowed to search for the landing target before falling back to normal landing. - * - * @unit s - * @min 0.0 - * @max 100 - * @decimal 1 - * @increment 0.1 - * @group Precision Land - */ -PARAM_DEFINE_FLOAT(PLD_SRCH_TOUT, 10.0f); - -/** - * Maximum number of search attempts - * - * Maximum number of times to search for the landing target if it is lost during the precision landing. - * - * @min 0 - * @max 100 - * @group Precision Land - */ -PARAM_DEFINE_INT32(PLD_MAX_SRCH, 3); diff --git a/src/modules/navigator/precland_params.yaml b/src/modules/navigator/precland_params.yaml new file mode 100644 index 0000000000..979123c4dc --- /dev/null +++ b/src/modules/navigator/precland_params.yaml @@ -0,0 +1,72 @@ +module_name: navigator +parameters: +- group: Precision Land + definitions: + PLD_BTOUT: + description: + short: Landing Target Timeout + long: Time after which the landing target is considered lost without any new + measurements. + type: float + default: 5.0 + unit: s + min: 0.0 + max: 50 + decimal: 1 + increment: 0.5 + PLD_HACC_RAD: + description: + short: Horizontal acceptance radius + long: Start descending if closer above landing target than this. + type: float + default: 0.2 + unit: m + min: 0.0 + max: 10 + decimal: 2 + increment: 0.1 + PLD_FAPPR_ALT: + description: + short: Final approach altitude + long: Allow final approach (without horizontal positioning) if losing landing + target closer than this to the ground. + type: float + default: 0.1 + unit: m + min: 0.0 + max: 10 + decimal: 2 + increment: 0.1 + PLD_SRCH_ALT: + description: + short: Search altitude + long: Altitude above home to which to climb when searching for the landing + target. + type: float + default: 10.0 + unit: m + min: 0.0 + max: 100 + decimal: 1 + increment: 0.1 + PLD_SRCH_TOUT: + description: + short: Search timeout + long: Time allowed to search for the landing target before falling back to + normal landing. + type: float + default: 10.0 + unit: s + min: 0.0 + max: 100 + decimal: 1 + increment: 0.1 + PLD_MAX_SRCH: + description: + short: Maximum number of search attempts + long: Maximum number of times to search for the landing target if it is lost + during the precision landing. + type: int32 + default: 3 + min: 0 + max: 100 diff --git a/src/modules/navigator/rtl_params.c b/src/modules/navigator/rtl_params.c deleted file mode 100644 index 0216f6606d..0000000000 --- a/src/modules/navigator/rtl_params.c +++ /dev/null @@ -1,203 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file rtl_params.c - * - * Parameters for return mode - * - * @author Julian Oes - */ - -/* - * Return mode parameters, accessible via MAVLink - */ - -/** - * Return mode return altitude - * - * Default minimum altitude above destination (e.g. home, safe point, landing pattern) for return flight. - * The vehicle will climb to this altitude when Return mode is enganged, unless it currently is flying higher already. - * This is affected by RTL_MIN_DIST and RTL_CONE_ANG. - * - * @unit m - * @min 0 - * @decimal 1 - * @increment 0.5 - * @group Return Mode - */ -PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 60.f); - - -/** - * Return mode loiter altitude - * - * Descend to this altitude (above destination position) after return, and wait for time defined in RTL_LAND_DELAY. - * Land (i.e. slowly descend) from this altitude if autolanding allowed. - * VTOLs do transition to hover in this altitdue above the landing point. - * - * @unit m - * @min 0 - * @decimal 1 - * @increment 0.5 - * @group Return Mode - */ -PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 30.f); - -/** - * Return mode delay - * - * Delay before landing (after initial descent) in Return mode. - * If set to -1 the system will not land but loiter at RTL_DESCEND_ALT. - * - * @unit s - * @min -1 - * @decimal 1 - * @increment 0.5 - * @group Return Mode - */ -PARAM_DEFINE_FLOAT(RTL_LAND_DELAY, 0.0f); - -/** - * Horizontal radius from return point within which special rules for return mode apply. - * - * The return altitude will be calculated based on RTL_CONE_ANG parameter. - * The yaw setpoint will switch to the one defined by corresponding waypoint. - * - * - * @unit m - * @min 0.5 - * @decimal 1 - * @increment 0.5 - * @group Return Mode - */ -PARAM_DEFINE_FLOAT(RTL_MIN_DIST, 10.0f); - -/** - * Return type - * - * Return mode destination and flight path (home location, rally point, mission landing pattern, reverse mission) - * - * @value 0 Return to closest safe point (home or rally point) via direct path. - * @value 1 Return to closest safe point other than home (mission landing pattern or rally point), via direct path. If no mission landing or rally points are defined return home via direct path. Always choose closest safe landing point if vehicle is a VTOL in hover mode. - * @value 2 Return to a planned mission landing, if available, using the mission path, else return to home via the reverse mission path. Do not consider rally points. - * @value 3 Return via direct path to closest destination: home, start of mission landing pattern or safe point. If the destination is a mission landing pattern, follow the pattern to land. - * @value 4 Return to the planned mission landing, or to home via the reverse mission path, whichever is closer by counting waypoints. Do not consider rally points. - * @value 5 Return directly to safe landing point (do not consider mission landing and Home) - * @group Return Mode - */ -PARAM_DEFINE_INT32(RTL_TYPE, 0); - -/** - * Half-angle of the return mode altitude cone - * - * Defines the half-angle of a cone centered around the destination position that - * affects the altitude at which the vehicle returns. - * - * @unit deg - * @min 0 - * @max 90 - * @value 0 No cone, always climb to RTL_RETURN_ALT above destination. - * @value 25 25 degrees half cone angle. - * @value 45 45 degrees half cone angle. - * @value 65 65 degrees half cone angle. - * @value 80 80 degrees half cone angle. - * @value 90 Only climb to at least RTL_DESCEND_ALT above destination. - * @group Return Mode - */ -PARAM_DEFINE_INT32(RTL_CONE_ANG, 45); - -/** - * RTL precision land mode - * - * Use precision landing when doing an RTL landing phase. - * This setting does not apply for RTL destinations planned as part of a mission. - * - * @value 0 No precision landing - * @value 1 Opportunistic precision landing - * @value 2 Required precision landing - * @group Return Mode - */ -PARAM_DEFINE_INT32(RTL_PLD_MD, 0); - -/** - * Loiter radius for rtl descend - * - * Set the radius for loitering to a safe altitude for VTOL transition. - * - * @unit m - * @min 25 - * @decimal 1 - * @increment 0.5 - * @group Return Mode - */ -PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 80.0f); - -/** - * RTL time estimate safety margin factor - * - * Safety factor that is used to scale the actual RTL time estimate. - * Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN - * - * @min 1.0 - * @max 2.0 - * @decimal 1 - * @increment 0.1 - * @group Return To Land - */ -PARAM_DEFINE_FLOAT(RTL_TIME_FACTOR, 1.1f); - -/** - * RTL time estimate safety margin offset - * - * Margin that is added to the time estimate, after it has already been scaled - * Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN - * - * @unit s - * @min 0 - * @max 3600 - * @decimal 1 - * @increment 1 - * @group Return To Land - */ -PARAM_DEFINE_INT32(RTL_TIME_MARGIN, 100); - -/** - * RTL force approach landing - * - * Only consider RTL point, if it has an approach defined. - * - * @boolean - * @group Return To Land - */ -PARAM_DEFINE_INT32(RTL_APPR_FORCE, 0); diff --git a/src/modules/navigator/rtl_params.yaml b/src/modules/navigator/rtl_params.yaml new file mode 100644 index 0000000000..ffe11e67a8 --- /dev/null +++ b/src/modules/navigator/rtl_params.yaml @@ -0,0 +1,152 @@ +module_name: navigator +parameters: +- group: Return Mode + definitions: + RTL_RETURN_ALT: + description: + short: Return mode return altitude + long: |- + Default minimum altitude above destination (e.g. home, safe point, landing pattern) for return flight. + The vehicle will climb to this altitude when Return mode is enganged, unless it currently is flying higher already. + This is affected by RTL_MIN_DIST and RTL_CONE_ANG. + type: float + default: 60.0 + unit: m + min: 0 + decimal: 1 + increment: 0.5 + RTL_DESCEND_ALT: + description: + short: Return mode loiter altitude + long: |- + Descend to this altitude (above destination position) after return, and wait for time defined in RTL_LAND_DELAY. + Land (i.e. slowly descend) from this altitude if autolanding allowed. + VTOLs do transition to hover in this altitdue above the landing point. + type: float + default: 30.0 + unit: m + min: 0 + decimal: 1 + increment: 0.5 + RTL_LAND_DELAY: + description: + short: Return mode delay + long: |- + Delay before landing (after initial descent) in Return mode. + If set to -1 the system will not land but loiter at RTL_DESCEND_ALT. + type: float + default: 0.0 + unit: s + min: -1 + decimal: 1 + increment: 0.5 + RTL_MIN_DIST: + description: + short: Min distance for RTL cone altitude calculation + long: |- + Horizontal radius from return point within which special rules for return mode apply + + The return altitude will be calculated based on RTL_CONE_ANG parameter. + The yaw setpoint will switch to the one defined by corresponding waypoint. + type: float + default: 10.0 + unit: m + min: 0.5 + decimal: 1 + increment: 0.5 + RTL_TYPE: + description: + short: Return type + long: Return mode destination and flight path (home location, rally point, + mission landing pattern, reverse mission) + type: enum + values: + 0: Return to closest safe point (home or rally point) via direct path. + 1: Return to closest safe point other than home (mission landing pattern or + rally point), via direct path. If no mission landing or rally points are + defined return home via direct path. Always choose closest safe landing + point if vehicle is a VTOL in hover mode. + 2: Return to a planned mission landing, if available, using the mission path, + else return to home via the reverse mission path. Do not consider rally + points. + 3: 'Return via direct path to closest destination: home, start of mission + landing pattern or safe point. If the destination is a mission landing pattern, + follow the pattern to land.' + 4: Return to the planned mission landing, or to home via the reverse mission + path, whichever is closer by counting waypoints. Do not consider rally points. + 5: Return directly to safe landing point (do not consider mission landing + and Home) + default: 0 + RTL_CONE_ANG: + description: + short: Half-angle of the return mode altitude cone + long: |- + Defines the half-angle of a cone centered around the destination position that + affects the altitude at which the vehicle returns. + type: enum + values: + 0: No cone, always climb to RTL_RETURN_ALT above destination. + 25: 25 degrees half cone angle. + 45: 45 degrees half cone angle. + 65: 65 degrees half cone angle. + 80: 80 degrees half cone angle. + 90: Only climb to at least RTL_DESCEND_ALT above destination. + default: 45 + unit: deg + min: 0 + max: 90 + RTL_PLD_MD: + description: + short: RTL precision land mode + long: |- + Use precision landing when doing an RTL landing phase. + This setting does not apply for RTL destinations planned as part of a mission. + type: enum + values: + 0: No precision landing + 1: Opportunistic precision landing + 2: Required precision landing + default: 0 + RTL_LOITER_RAD: + description: + short: Loiter radius for rtl descend + long: Set the radius for loitering to a safe altitude for VTOL transition. + type: float + default: 80.0 + unit: m + min: 25 + decimal: 1 + increment: 0.5 +- group: Return To Land + definitions: + RTL_TIME_FACTOR: + description: + short: RTL time estimate safety margin factor + long: |- + Safety factor that is used to scale the actual RTL time estimate. + Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN + type: float + default: 1.1 + min: 1.0 + max: 2.0 + decimal: 1 + increment: 0.1 + RTL_TIME_MARGIN: + description: + short: RTL time estimate safety margin offset + long: |- + Margin that is added to the time estimate, after it has already been scaled + Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN + type: int32 + default: 100 + unit: s + min: 0 + max: 3600 + decimal: 1 + increment: 1 + RTL_APPR_FORCE: + description: + short: RTL force approach landing + long: Only consider RTL point, if it has an approach defined. + type: boolean + default: 0 diff --git a/src/modules/navigator/vtol_takeoff_params.c b/src/modules/navigator/vtol_takeoff_params.c deleted file mode 100644 index b33818f9d6..0000000000 --- a/src/modules/navigator/vtol_takeoff_params.c +++ /dev/null @@ -1,53 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file vtol_takeoff_params.c - * - * Parameters for the VTOL takeoff navigation mode. - * - */ - -/** - * VTOL Takeoff relative loiter altitude. - * - * Altitude relative to home at which vehicle will loiter after front transition. - * - * @unit m - * @min 20 - * @max 300 - * @decimal 1 - * @increment 1 - * @group VTOL Takeoff - */ -PARAM_DEFINE_FLOAT(VTO_LOITER_ALT, 80); diff --git a/src/modules/navigator/vtol_takeoff_params.yaml b/src/modules/navigator/vtol_takeoff_params.yaml new file mode 100644 index 0000000000..2841beec6e --- /dev/null +++ b/src/modules/navigator/vtol_takeoff_params.yaml @@ -0,0 +1,15 @@ +module_name: navigator +parameters: +- group: VTOL Takeoff + definitions: + VTO_LOITER_ALT: + description: + short: VTOL Takeoff relative loiter altitude + long: Altitude relative to home at which vehicle will loiter after front transition. + type: float + default: 80 + unit: m + min: 20 + max: 300 + decimal: 1 + increment: 1