mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-04 21:23:57 +08:00
@@ -133,7 +133,7 @@ class SourceParser(object):
|
|||||||
re_remove_dots = re.compile(r'\.+$')
|
re_remove_dots = re.compile(r'\.+$')
|
||||||
re_remove_carriage_return = re.compile('\n+')
|
re_remove_carriage_return = re.compile('\n+')
|
||||||
|
|
||||||
valid_tags = set(["group", "board", "min", "max", "unit", "decimal", "increment", "reboot_required", "value"])
|
valid_tags = set(["group", "board", "min", "max", "unit", "decimal", "increment", "reboot_required", "value", "boolean"])
|
||||||
|
|
||||||
# Order of parameter groups
|
# Order of parameter groups
|
||||||
priority = {
|
priority = {
|
||||||
|
|||||||
@@ -58,7 +58,6 @@ PARAM_DEFINE_FLOAT(TRIG_INTERVAL, 40.0f);
|
|||||||
*
|
*
|
||||||
* This parameter sets the polarity of the trigger (0 = ACTIVE_LOW, 1 = ACTIVE_HIGH )
|
* This parameter sets the polarity of the trigger (0 = ACTIVE_LOW, 1 = ACTIVE_HIGH )
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value 0 ACTIVE_LOW
|
* @value 0 ACTIVE_LOW
|
||||||
* @value 1 ACTIVE_HIGH
|
* @value 1 ACTIVE_HIGH
|
||||||
* @min 0
|
* @min 0
|
||||||
@@ -82,11 +81,10 @@ PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 0.5f);
|
|||||||
*
|
*
|
||||||
* 0 disables the trigger, 1 sets it to enabled on command, 2 always on, 3 distance based, 4 distance based enabled on command
|
* 0 disables the trigger, 1 sets it to enabled on command, 2 always on, 3 distance based, 4 distance based enabled on command
|
||||||
*
|
*
|
||||||
* @unit enum
|
* @value 0 Disable
|
||||||
* @value 0 disable
|
* @value 1 CMD
|
||||||
* @value 1 cmd
|
* @value 2 Always
|
||||||
* @value 2 always
|
* @value 3 Distance
|
||||||
* @value 3 distance
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 4
|
* @max 4
|
||||||
* @group Camera trigger
|
* @group Camera trigger
|
||||||
|
|||||||
@@ -48,7 +48,7 @@
|
|||||||
*
|
*
|
||||||
* If set to 1, mount mode will be enforced.
|
* If set to 1, mount mode will be enforced.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Gimbal
|
* @group Gimbal
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(GMB_USE_MNT, 0);
|
PARAM_DEFINE_INT32(GMB_USE_MNT, 0);
|
||||||
@@ -63,11 +63,10 @@ PARAM_DEFINE_INT32(GMB_USE_MNT, 0);
|
|||||||
* Switch on means the gimbal can move freely, and landing gear
|
* Switch on means the gimbal can move freely, and landing gear
|
||||||
* will be retracted if applicable.
|
* will be retracted if applicable.
|
||||||
*
|
*
|
||||||
* @unit enum
|
* @value 0 Disable
|
||||||
* @value 0 disable
|
* @value 1 AUX1
|
||||||
* @value 1 aux1
|
* @value 2 AUX2
|
||||||
* @value 2 aux2
|
* @value 3 AUX3
|
||||||
* @value 3 aux3
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 3
|
* @max 3
|
||||||
* @group Gimbal
|
* @group Gimbal
|
||||||
|
|||||||
@@ -46,7 +46,6 @@
|
|||||||
/**
|
/**
|
||||||
* Enables testmode (Identify) of MKBLCTRL Driver
|
* Enables testmode (Identify) of MKBLCTRL Driver
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value 0 Disabled
|
* @value 0 Disabled
|
||||||
* @value 1 Enabled
|
* @value 1 Enabled
|
||||||
* @min 0
|
* @min 0
|
||||||
|
|||||||
@@ -48,7 +48,7 @@
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_AUX_REV1, 0);
|
PARAM_DEFINE_INT32(PWM_AUX_REV1, 0);
|
||||||
@@ -59,7 +59,7 @@ PARAM_DEFINE_INT32(PWM_AUX_REV1, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_AUX_REV2, 0);
|
PARAM_DEFINE_INT32(PWM_AUX_REV2, 0);
|
||||||
@@ -70,7 +70,7 @@ PARAM_DEFINE_INT32(PWM_AUX_REV2, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_AUX_REV3, 0);
|
PARAM_DEFINE_INT32(PWM_AUX_REV3, 0);
|
||||||
@@ -81,7 +81,7 @@ PARAM_DEFINE_INT32(PWM_AUX_REV3, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_AUX_REV4, 0);
|
PARAM_DEFINE_INT32(PWM_AUX_REV4, 0);
|
||||||
@@ -92,7 +92,7 @@ PARAM_DEFINE_INT32(PWM_AUX_REV4, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_AUX_REV5, 0);
|
PARAM_DEFINE_INT32(PWM_AUX_REV5, 0);
|
||||||
@@ -103,7 +103,7 @@ PARAM_DEFINE_INT32(PWM_AUX_REV5, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_AUX_REV6, 0);
|
PARAM_DEFINE_INT32(PWM_AUX_REV6, 0);
|
||||||
|
|||||||
@@ -48,7 +48,7 @@
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_MAIN_REV1, 0);
|
PARAM_DEFINE_INT32(PWM_MAIN_REV1, 0);
|
||||||
@@ -59,7 +59,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV1, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_MAIN_REV2, 0);
|
PARAM_DEFINE_INT32(PWM_MAIN_REV2, 0);
|
||||||
@@ -70,7 +70,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV2, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_MAIN_REV3, 0);
|
PARAM_DEFINE_INT32(PWM_MAIN_REV3, 0);
|
||||||
@@ -81,7 +81,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV3, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_MAIN_REV4, 0);
|
PARAM_DEFINE_INT32(PWM_MAIN_REV4, 0);
|
||||||
@@ -92,7 +92,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV4, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_MAIN_REV5, 0);
|
PARAM_DEFINE_INT32(PWM_MAIN_REV5, 0);
|
||||||
@@ -103,7 +103,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV5, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_MAIN_REV6, 0);
|
PARAM_DEFINE_INT32(PWM_MAIN_REV6, 0);
|
||||||
@@ -114,7 +114,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV6, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0);
|
PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0);
|
||||||
@@ -125,7 +125,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0);
|
|||||||
* Set to 1 to invert the channel, 0 for default direction.
|
* Set to 1 to invert the channel, 0 for default direction.
|
||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_MAIN_REV8, 0);
|
PARAM_DEFINE_INT32(PWM_MAIN_REV8, 0);
|
||||||
@@ -135,7 +135,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV8, 0);
|
|||||||
*
|
*
|
||||||
* Set to 1 to enable S.BUS version 1 output instead of RSSI.
|
* Set to 1 to enable S.BUS version 1 output instead of RSSI.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group PWM Outputs
|
* @group PWM Outputs
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(PWM_SBUS_MODE, 0);
|
PARAM_DEFINE_INT32(PWM_SBUS_MODE, 0);
|
||||||
|
|||||||
@@ -47,7 +47,7 @@
|
|||||||
/**
|
/**
|
||||||
* Enable launch detection.
|
* Enable launch detection.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 1
|
* @max 1
|
||||||
* @group Launch detection
|
* @group Launch detection
|
||||||
|
|||||||
@@ -44,7 +44,7 @@
|
|||||||
*
|
*
|
||||||
* 0: disabled, 1: enabled
|
* 0: disabled, 1: enabled
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Runway Takeoff
|
* @group Runway Takeoff
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(RWTO_TKOFF, 0);
|
PARAM_DEFINE_INT32(RWTO_TKOFF, 0);
|
||||||
@@ -54,9 +54,8 @@ PARAM_DEFINE_INT32(RWTO_TKOFF, 0);
|
|||||||
*
|
*
|
||||||
* 0: airframe heading, 1: heading towards takeoff waypoint
|
* 0: airframe heading, 1: heading towards takeoff waypoint
|
||||||
*
|
*
|
||||||
* @unit enum
|
* @value 0 Airframe
|
||||||
* @value 0 airframe
|
* @value 1 Waypoint
|
||||||
* @value 1 waypoint
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 1
|
* @max 1
|
||||||
* @group Runway Takeoff
|
* @group Runway Takeoff
|
||||||
|
|||||||
@@ -97,7 +97,7 @@ PARAM_DEFINE_FLOAT(ATT_MAG_DECL, 0.0f);
|
|||||||
* Enable automatic GPS based declination compensation
|
* Enable automatic GPS based declination compensation
|
||||||
*
|
*
|
||||||
* @group Attitude Q estimator
|
* @group Attitude Q estimator
|
||||||
* @unit boolean
|
* @boolean
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1);
|
PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1);
|
||||||
|
|
||||||
@@ -107,10 +107,9 @@ PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1);
|
|||||||
* Set to 2 to use heading from motion capture.
|
* Set to 2 to use heading from motion capture.
|
||||||
*
|
*
|
||||||
* @group Attitude Q estimator
|
* @group Attitude Q estimator
|
||||||
* @unit enum
|
* @value 0 None
|
||||||
* @value 0 none
|
* @value 1 Vision
|
||||||
* @value 1 vision
|
* @value 2 Motion Capture
|
||||||
* @value 2 motion capture
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 2
|
* @max 2
|
||||||
*/
|
*/
|
||||||
@@ -121,7 +120,7 @@ PARAM_DEFINE_INT32(ATT_EXT_HDG_M, 0);
|
|||||||
* velocity.
|
* velocity.
|
||||||
*
|
*
|
||||||
* @group Attitude Q estimator
|
* @group Attitude Q estimator
|
||||||
* @unit boolean
|
* @boolean
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(ATT_ACC_COMP, 1);
|
PARAM_DEFINE_INT32(ATT_ACC_COMP, 1);
|
||||||
|
|
||||||
|
|||||||
@@ -137,7 +137,7 @@ PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.07f);
|
|||||||
* Defines the number of cells the attached battery consists of.
|
* Defines the number of cells the attached battery consists of.
|
||||||
*
|
*
|
||||||
* @group Battery Calibration
|
* @group Battery Calibration
|
||||||
* @unit enum
|
* @unit S
|
||||||
* @min 2
|
* @min 2
|
||||||
* @max 10
|
* @max 10
|
||||||
* @value 2 2S Battery
|
* @value 2 2S Battery
|
||||||
@@ -178,7 +178,7 @@ PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f);
|
|||||||
* Set to 1 to enable actions triggered when the datalink is lost.
|
* Set to 1 to enable actions triggered when the datalink is lost.
|
||||||
*
|
*
|
||||||
* @group Commander
|
* @group Commander
|
||||||
* @unit boolean
|
* @boolean
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(COM_DL_LOSS_EN, 0);
|
PARAM_DEFINE_INT32(COM_DL_LOSS_EN, 0);
|
||||||
|
|
||||||
@@ -303,7 +303,7 @@ PARAM_DEFINE_FLOAT(COM_HOME_V_T, 10.0f);
|
|||||||
* being sticky. Developers can default it to off.
|
* being sticky. Developers can default it to off.
|
||||||
*
|
*
|
||||||
* @group Commander
|
* @group Commander
|
||||||
* @unit boolean
|
* @boolean
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(COM_AUTOS_PAR, 1);
|
PARAM_DEFINE_INT32(COM_AUTOS_PAR, 1);
|
||||||
|
|
||||||
@@ -316,7 +316,6 @@ PARAM_DEFINE_INT32(COM_AUTOS_PAR, 1);
|
|||||||
* of directly forwarding the manual input data.
|
* of directly forwarding the manual input data.
|
||||||
*
|
*
|
||||||
* @group Commander
|
* @group Commander
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 2
|
* @max 2
|
||||||
* @value 0 RC Transmitter
|
* @value 0 RC Transmitter
|
||||||
@@ -347,7 +346,6 @@ PARAM_DEFINE_INT32(COM_DISARM_LAND, 0);
|
|||||||
* If the main switch channel is in this range the
|
* If the main switch channel is in this range the
|
||||||
* selected flight mode will be applied.
|
* selected flight mode will be applied.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value -1 Unassigned
|
* @value -1 Unassigned
|
||||||
* @value 0 Manual
|
* @value 0 Manual
|
||||||
* @value 1 Altitude
|
* @value 1 Altitude
|
||||||
@@ -370,7 +368,6 @@ PARAM_DEFINE_INT32(COM_FLTMODE1, -1);
|
|||||||
* If the main switch channel is in this range the
|
* If the main switch channel is in this range the
|
||||||
* selected flight mode will be applied.
|
* selected flight mode will be applied.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value -1 Unassigned
|
* @value -1 Unassigned
|
||||||
* @value 0 Manual
|
* @value 0 Manual
|
||||||
* @value 1 Altitude
|
* @value 1 Altitude
|
||||||
@@ -393,7 +390,6 @@ PARAM_DEFINE_INT32(COM_FLTMODE2, -1);
|
|||||||
* If the main switch channel is in this range the
|
* If the main switch channel is in this range the
|
||||||
* selected flight mode will be applied.
|
* selected flight mode will be applied.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value -1 Unassigned
|
* @value -1 Unassigned
|
||||||
* @value 0 Manual
|
* @value 0 Manual
|
||||||
* @value 1 Altitude
|
* @value 1 Altitude
|
||||||
@@ -416,7 +412,6 @@ PARAM_DEFINE_INT32(COM_FLTMODE3, -1);
|
|||||||
* If the main switch channel is in this range the
|
* If the main switch channel is in this range the
|
||||||
* selected flight mode will be applied.
|
* selected flight mode will be applied.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value -1 Unassigned
|
* @value -1 Unassigned
|
||||||
* @value 0 Manual
|
* @value 0 Manual
|
||||||
* @value 1 Altitude
|
* @value 1 Altitude
|
||||||
@@ -439,7 +434,6 @@ PARAM_DEFINE_INT32(COM_FLTMODE4, -1);
|
|||||||
* If the main switch channel is in this range the
|
* If the main switch channel is in this range the
|
||||||
* selected flight mode will be applied.
|
* selected flight mode will be applied.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value -1 Unassigned
|
* @value -1 Unassigned
|
||||||
* @value 0 Manual
|
* @value 0 Manual
|
||||||
* @value 1 Altitude
|
* @value 1 Altitude
|
||||||
@@ -457,12 +451,11 @@ PARAM_DEFINE_INT32(COM_FLTMODE4, -1);
|
|||||||
PARAM_DEFINE_INT32(COM_FLTMODE5, -1);
|
PARAM_DEFINE_INT32(COM_FLTMODE5, -1);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Sixt flightmode slot (1800-2000)
|
* Sixth flightmode slot (1800-2000)
|
||||||
*
|
*
|
||||||
* If the main switch channel is in this range the
|
* If the main switch channel is in this range the
|
||||||
* selected flight mode will be applied.
|
* selected flight mode will be applied.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value -1 Unassigned
|
* @value -1 Unassigned
|
||||||
* @value 0 Manual
|
* @value 0 Manual
|
||||||
* @value 1 Altitude
|
* @value 1 Altitude
|
||||||
|
|||||||
@@ -345,7 +345,6 @@ PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 7);
|
|||||||
* If set to automatic: heading fusion on-ground and 3-axis fusion in-flight
|
* If set to automatic: heading fusion on-ground and 3-axis fusion in-flight
|
||||||
*
|
*
|
||||||
* @group EKF2
|
* @group EKF2
|
||||||
* @unit enum
|
|
||||||
* @value 0 Automatic
|
* @value 0 Automatic
|
||||||
* @value 1 Magnetic heading
|
* @value 1 Magnetic heading
|
||||||
* @value 2 3-axis fusion
|
* @value 2 3-axis fusion
|
||||||
@@ -387,7 +386,7 @@ PARAM_DEFINE_FLOAT(EKF2_GPS_V_GATE, 3.0f);
|
|||||||
* replay messages for logging.
|
* replay messages for logging.
|
||||||
*
|
*
|
||||||
* @group EKF2
|
* @group EKF2
|
||||||
* @unit boolean
|
* @boolean
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(EKF2_REC_RPL, 0);
|
PARAM_DEFINE_INT32(EKF2_REC_RPL, 0);
|
||||||
|
|
||||||
|
|||||||
@@ -83,6 +83,7 @@ PARAM_DEFINE_FLOAT(FW_P_TC, 0.4f);
|
|||||||
* This defines how much the elevator input will be commanded depending on the
|
* This defines how much the elevator input will be commanded depending on the
|
||||||
* current body angular rate error.
|
* current body angular rate error.
|
||||||
*
|
*
|
||||||
|
* @unit %/rad/s
|
||||||
* @min 0.005
|
* @min 0.005
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -95,6 +96,7 @@ PARAM_DEFINE_FLOAT(FW_PR_P, 0.08f);
|
|||||||
* This gain defines how much control response will result out of a steady
|
* This gain defines how much control response will result out of a steady
|
||||||
* state error. It trims any constant error.
|
* state error. It trims any constant error.
|
||||||
*
|
*
|
||||||
|
* @unit %/rad
|
||||||
* @min 0.005
|
* @min 0.005
|
||||||
* @max 0.5
|
* @max 0.5
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -133,6 +135,7 @@ PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 60.0f);
|
|||||||
* The portion of the integrator part in the control surface deflection is
|
* The portion of the integrator part in the control surface deflection is
|
||||||
* limited to this value
|
* limited to this value
|
||||||
*
|
*
|
||||||
|
* @unit %
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -145,6 +148,7 @@ PARAM_DEFINE_FLOAT(FW_PR_IMAX, 0.4f);
|
|||||||
* This defines how much the aileron input will be commanded depending on the
|
* This defines how much the aileron input will be commanded depending on the
|
||||||
* current body angular rate error.
|
* current body angular rate error.
|
||||||
*
|
*
|
||||||
|
* @unit %/rad/s
|
||||||
* @min 0.005
|
* @min 0.005
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -157,6 +161,7 @@ PARAM_DEFINE_FLOAT(FW_RR_P, 0.05f);
|
|||||||
* This gain defines how much control response will result out of a steady
|
* This gain defines how much control response will result out of a steady
|
||||||
* state error. It trims any constant error.
|
* state error. It trims any constant error.
|
||||||
*
|
*
|
||||||
|
* @unit %/rad
|
||||||
* @min 0.005
|
* @min 0.005
|
||||||
* @max 0.2
|
* @max 0.2
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -168,6 +173,7 @@ PARAM_DEFINE_FLOAT(FW_RR_I, 0.01f);
|
|||||||
*
|
*
|
||||||
* The portion of the integrator part in the control surface deflection is limited to this value.
|
* The portion of the integrator part in the control surface deflection is limited to this value.
|
||||||
*
|
*
|
||||||
|
* @unit %
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -193,6 +199,7 @@ PARAM_DEFINE_FLOAT(FW_R_RMAX, 70.0f);
|
|||||||
* This defines how much the rudder input will be commanded depending on the
|
* This defines how much the rudder input will be commanded depending on the
|
||||||
* current body angular rate error.
|
* current body angular rate error.
|
||||||
*
|
*
|
||||||
|
* @unit %/rad/s
|
||||||
* @min 0.005
|
* @min 0.005
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -205,6 +212,7 @@ PARAM_DEFINE_FLOAT(FW_YR_P, 0.05f);
|
|||||||
* This gain defines how much control response will result out of a steady
|
* This gain defines how much control response will result out of a steady
|
||||||
* state error. It trims any constant error.
|
* state error. It trims any constant error.
|
||||||
*
|
*
|
||||||
|
* @unit %/rad
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 50.0
|
* @max 50.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -217,6 +225,7 @@ PARAM_DEFINE_FLOAT(FW_YR_I, 0.0f);
|
|||||||
* The portion of the integrator part in the control surface deflection is
|
* The portion of the integrator part in the control surface deflection is
|
||||||
* limited to this value
|
* limited to this value
|
||||||
*
|
*
|
||||||
|
* @unit %
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -242,6 +251,7 @@ PARAM_DEFINE_FLOAT(FW_Y_RMAX, 0.0f);
|
|||||||
* This defines how much the wheel steering input will be commanded depending on the
|
* This defines how much the wheel steering input will be commanded depending on the
|
||||||
* current body angular rate error.
|
* current body angular rate error.
|
||||||
*
|
*
|
||||||
|
* @unit %/rad/s
|
||||||
* @min 0.005
|
* @min 0.005
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -254,6 +264,7 @@ PARAM_DEFINE_FLOAT(FW_WR_P, 0.5f);
|
|||||||
* This gain defines how much control response will result out of a steady
|
* This gain defines how much control response will result out of a steady
|
||||||
* state error. It trims any constant error.
|
* state error. It trims any constant error.
|
||||||
*
|
*
|
||||||
|
* @unit %/rad
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 50.0
|
* @max 50.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -266,6 +277,7 @@ PARAM_DEFINE_FLOAT(FW_WR_I, 0.1f);
|
|||||||
* The portion of the integrator part in the control surface deflection is
|
* The portion of the integrator part in the control surface deflection is
|
||||||
* limited to this value
|
* limited to this value
|
||||||
*
|
*
|
||||||
|
* @unit %
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -292,6 +304,7 @@ PARAM_DEFINE_FLOAT(FW_W_RMAX, 0.0f);
|
|||||||
* to obtain a tigher response of the controller without introducing
|
* to obtain a tigher response of the controller without introducing
|
||||||
* noise amplification.
|
* noise amplification.
|
||||||
*
|
*
|
||||||
|
* @unit %/rad/s
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 10.0
|
* @max 10.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -303,6 +316,7 @@ PARAM_DEFINE_FLOAT(FW_RR_FF, 0.5f);
|
|||||||
*
|
*
|
||||||
* Direct feed forward from rate setpoint to control surface output
|
* Direct feed forward from rate setpoint to control surface output
|
||||||
*
|
*
|
||||||
|
* @unit %/rad/s
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 10.0
|
* @max 10.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -314,6 +328,7 @@ PARAM_DEFINE_FLOAT(FW_PR_FF, 0.5f);
|
|||||||
*
|
*
|
||||||
* Direct feed forward from rate setpoint to control surface output
|
* Direct feed forward from rate setpoint to control surface output
|
||||||
*
|
*
|
||||||
|
* @unit %/rad/s
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 10.0
|
* @max 10.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -325,6 +340,7 @@ PARAM_DEFINE_FLOAT(FW_YR_FF, 0.3f);
|
|||||||
*
|
*
|
||||||
* Direct feed forward from rate setpoint to control surface output
|
* Direct feed forward from rate setpoint to control surface output
|
||||||
*
|
*
|
||||||
|
* @unit %/rad/s
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 10.0
|
* @max 10.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
@@ -349,7 +365,6 @@ PARAM_DEFINE_FLOAT(FW_YCO_VMIN, 1000.0f);
|
|||||||
* 0: open-loop zero lateral acceleration based on kinematic constraints
|
* 0: open-loop zero lateral acceleration based on kinematic constraints
|
||||||
* 1: closed-loop: try to reduce lateral acceleration to 0 by measuring the acceleration
|
* 1: closed-loop: try to reduce lateral acceleration to 0 by measuring the acceleration
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 1
|
* @max 1
|
||||||
* @value 0 open-loop
|
* @value 0 open-loop
|
||||||
|
|||||||
@@ -54,7 +54,7 @@
|
|||||||
* @unit m
|
* @unit m
|
||||||
* @min 12.0
|
* @min 12.0
|
||||||
* @max 50.0
|
* @max 50.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 20.0f);
|
PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 20.0f);
|
||||||
|
|
||||||
@@ -65,7 +65,7 @@ PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 20.0f);
|
|||||||
*
|
*
|
||||||
* @min 0.6
|
* @min 0.6
|
||||||
* @max 0.9
|
* @max 0.9
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
|
PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
|
||||||
|
|
||||||
@@ -76,7 +76,7 @@ PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
|
|||||||
*
|
*
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.6f);
|
PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.6f);
|
||||||
|
|
||||||
@@ -87,7 +87,7 @@ PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.6f);
|
|||||||
*
|
*
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f);
|
PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f);
|
||||||
|
|
||||||
@@ -99,7 +99,7 @@ PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f);
|
|||||||
* @unit deg
|
* @unit deg
|
||||||
* @min -60.0
|
* @min -60.0
|
||||||
* @max 0.0
|
* @max 0.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f);
|
PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f);
|
||||||
|
|
||||||
@@ -111,7 +111,7 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f);
|
|||||||
* @unit deg
|
* @unit deg
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 60.0
|
* @max 60.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f);
|
PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f);
|
||||||
|
|
||||||
@@ -123,7 +123,7 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f);
|
|||||||
* @unit deg
|
* @unit deg
|
||||||
* @min 35.0
|
* @min 35.0
|
||||||
* @max 65.0
|
* @max 65.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f);
|
PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f);
|
||||||
|
|
||||||
@@ -136,7 +136,7 @@ PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f);
|
|||||||
*
|
*
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
|
PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
|
||||||
|
|
||||||
@@ -154,7 +154,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
|
|||||||
*
|
*
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
|
PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
|
||||||
|
|
||||||
@@ -168,7 +168,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
|
|||||||
*
|
*
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 0.4
|
* @max 0.4
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_THR_IDLE, 0.15f);
|
PARAM_DEFINE_FLOAT(FW_THR_IDLE, 0.15f);
|
||||||
|
|
||||||
@@ -180,7 +180,7 @@ PARAM_DEFINE_FLOAT(FW_THR_IDLE, 0.15f);
|
|||||||
*
|
*
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f);
|
PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f);
|
||||||
|
|
||||||
@@ -195,7 +195,7 @@ PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f);
|
|||||||
* @unit m
|
* @unit m
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 150.0
|
* @max 150.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_CLMBOUT_DIFF, 10.0f);
|
PARAM_DEFINE_FLOAT(FW_CLMBOUT_DIFF, 10.0f);
|
||||||
|
|
||||||
@@ -218,7 +218,7 @@ PARAM_DEFINE_FLOAT(FW_CLMBOUT_DIFF, 10.0f);
|
|||||||
* @unit m/s
|
* @unit m/s
|
||||||
* @min 2.0
|
* @min 2.0
|
||||||
* @max 10.0
|
* @max 10.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
|
PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
|
||||||
|
|
||||||
@@ -230,7 +230,7 @@ PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
|
|||||||
* to measure FW_T_CLMB_MAX.
|
* to measure FW_T_CLMB_MAX.
|
||||||
*
|
*
|
||||||
* @unit m/s
|
* @unit m/s
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f);
|
PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f);
|
||||||
|
|
||||||
@@ -244,7 +244,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f);
|
|||||||
* the aircraft.
|
* the aircraft.
|
||||||
*
|
*
|
||||||
* @unit m/s
|
* @unit m/s
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
|
PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
|
||||||
|
|
||||||
@@ -256,7 +256,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
|
|||||||
* to respond.
|
* to respond.
|
||||||
*
|
*
|
||||||
* @unit s
|
* @unit s
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
|
PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
|
||||||
|
|
||||||
@@ -268,7 +268,7 @@ PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
|
|||||||
* to respond.
|
* to respond.
|
||||||
*
|
*
|
||||||
* @unit s
|
* @unit s
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_THRO_CONST, 8.0f);
|
PARAM_DEFINE_FLOAT(FW_T_THRO_CONST, 8.0f);
|
||||||
|
|
||||||
@@ -278,7 +278,7 @@ PARAM_DEFINE_FLOAT(FW_T_THRO_CONST, 8.0f);
|
|||||||
* This is the damping gain for the throttle demand loop.
|
* This is the damping gain for the throttle demand loop.
|
||||||
* Increase to add damping to correct for oscillations in speed and height.
|
* Increase to add damping to correct for oscillations in speed and height.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
|
PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
|
||||||
|
|
||||||
@@ -290,7 +290,7 @@ PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
|
|||||||
* and height offsets are trimmed out, but reduces damping and
|
* and height offsets are trimmed out, but reduces damping and
|
||||||
* increases overshoot.
|
* increases overshoot.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
|
PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
|
||||||
|
|
||||||
@@ -304,7 +304,7 @@ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
|
|||||||
* from under-speed conditions.
|
* from under-speed conditions.
|
||||||
*
|
*
|
||||||
* @unit m/s/s
|
* @unit m/s/s
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
|
PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
|
||||||
|
|
||||||
@@ -318,7 +318,7 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
|
|||||||
* the solution more towards use of the accelerometer data.
|
* the solution more towards use of the accelerometer data.
|
||||||
*
|
*
|
||||||
* @unit rad/s
|
* @unit rad/s
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
|
PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
|
||||||
|
|
||||||
@@ -332,7 +332,7 @@ PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
|
|||||||
* solution more towards use of the accelerometer data.
|
* solution more towards use of the accelerometer data.
|
||||||
*
|
*
|
||||||
* @unit rad/s
|
* @unit rad/s
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
|
PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
|
||||||
|
|
||||||
@@ -348,7 +348,7 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
|
|||||||
* aircraft (eg powered sailplanes) can use a lower value, whereas
|
* aircraft (eg powered sailplanes) can use a lower value, whereas
|
||||||
* inefficient low aspect-ratio models (eg delta wings) can use a higher value.
|
* inefficient low aspect-ratio models (eg delta wings) can use a higher value.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f);
|
PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f);
|
||||||
|
|
||||||
@@ -368,7 +368,7 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f);
|
|||||||
*
|
*
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 2.0
|
* @max 2.0
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
|
PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
|
||||||
|
|
||||||
@@ -380,28 +380,28 @@ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
|
|||||||
* will work well provided the pitch to servo controller has been tuned
|
* will work well provided the pitch to servo controller has been tuned
|
||||||
* properly.
|
* properly.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
|
PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Height rate P factor
|
* Height rate P factor
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
|
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Height rate FF factor
|
* Height rate FF factor
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.0f);
|
PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.0f);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Speed rate P factor
|
* Speed rate P factor
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group FW TECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.02f);
|
PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.02f);
|
||||||
|
|
||||||
@@ -411,7 +411,7 @@ PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.02f);
|
|||||||
* @unit deg
|
* @unit deg
|
||||||
* @min 1.0
|
* @min 1.0
|
||||||
* @max 15.0
|
* @max 15.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f);
|
PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f);
|
||||||
|
|
||||||
@@ -419,7 +419,7 @@ PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f);
|
|||||||
*
|
*
|
||||||
*
|
*
|
||||||
* @unit m
|
* @unit m
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f);
|
PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f);
|
||||||
|
|
||||||
@@ -429,7 +429,7 @@ PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f);
|
|||||||
* @unit m
|
* @unit m
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 25.0
|
* @max 25.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_FLALT, 8.0f);
|
PARAM_DEFINE_FLOAT(FW_LND_FLALT, 8.0f);
|
||||||
|
|
||||||
@@ -442,7 +442,7 @@ PARAM_DEFINE_FLOAT(FW_LND_FLALT, 8.0f);
|
|||||||
* @unit m
|
* @unit m
|
||||||
* @min -1.0
|
* @min -1.0
|
||||||
* @max 30.0
|
* @max 30.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_TLALT, -1.0f);
|
PARAM_DEFINE_FLOAT(FW_LND_TLALT, -1.0f);
|
||||||
|
|
||||||
@@ -452,7 +452,7 @@ PARAM_DEFINE_FLOAT(FW_LND_TLALT, -1.0f);
|
|||||||
* @unit m
|
* @unit m
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 30.0
|
* @max 30.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
|
PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
|
||||||
|
|
||||||
@@ -461,8 +461,8 @@ PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
|
|||||||
*
|
*
|
||||||
* 0: disabled, 1: enabled
|
* 0: disabled, 1: enabled
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(FW_LND_USETER, 0);
|
PARAM_DEFINE_INT32(FW_LND_USETER, 0);
|
||||||
|
|
||||||
@@ -475,7 +475,7 @@ PARAM_DEFINE_INT32(FW_LND_USETER, 0);
|
|||||||
* @unit deg
|
* @unit deg
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 15.0
|
* @max 15.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_FL_PMIN, 2.5f);
|
PARAM_DEFINE_FLOAT(FW_LND_FL_PMIN, 2.5f);
|
||||||
@@ -489,7 +489,7 @@ PARAM_DEFINE_FLOAT(FW_LND_FL_PMIN, 2.5f);
|
|||||||
* @unit deg
|
* @unit deg
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 45.0
|
* @max 45.0
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_FL_PMAX, 15.0f);
|
PARAM_DEFINE_FLOAT(FW_LND_FL_PMAX, 15.0f);
|
||||||
@@ -502,6 +502,6 @@ PARAM_DEFINE_FLOAT(FW_LND_FL_PMAX, 15.0f);
|
|||||||
*
|
*
|
||||||
* @min 1.0
|
* @min 1.0
|
||||||
* @max 1.5
|
* @max 1.5
|
||||||
* @group L1 Control
|
* @group FW L1 Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_AIRSPD_SC, 1.3f);
|
PARAM_DEFINE_FLOAT(FW_LND_AIRSPD_SC, 1.3f);
|
||||||
|
|||||||
@@ -47,7 +47,7 @@
|
|||||||
*
|
*
|
||||||
* Set to 1 to enable mTECS
|
* Set to 1 to enable mTECS
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group mTECS
|
* @group mTECS
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(MT_ENABLED, 0);
|
PARAM_DEFINE_INT32(MT_ENABLED, 0);
|
||||||
|
|||||||
@@ -6,7 +6,7 @@
|
|||||||
/**
|
/**
|
||||||
* Enable local position estimator.
|
* Enable local position estimator.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Local Position Estimator
|
* @group Local Position Estimator
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(LPE_ENABLED, 1);
|
PARAM_DEFINE_INT32(LPE_ENABLED, 1);
|
||||||
@@ -14,7 +14,7 @@ PARAM_DEFINE_INT32(LPE_ENABLED, 1);
|
|||||||
/**
|
/**
|
||||||
* Enable accelerometer integration for prediction.
|
* Enable accelerometer integration for prediction.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Local Position Estimator
|
* @group Local Position Estimator
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(LPE_INTEGRATE, 1);
|
PARAM_DEFINE_INT32(LPE_INTEGRATE, 1);
|
||||||
|
|||||||
@@ -74,7 +74,7 @@ PARAM_DEFINE_INT32(MAV_TYPE, 1);
|
|||||||
*
|
*
|
||||||
* If set to 1 incoming HIL GPS messages are parsed.
|
* If set to 1 incoming HIL GPS messages are parsed.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group MAVLink
|
* @group MAVLink
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(MAV_USEHILGPS, 0);
|
PARAM_DEFINE_INT32(MAV_USEHILGPS, 0);
|
||||||
@@ -85,7 +85,7 @@ PARAM_DEFINE_INT32(MAV_USEHILGPS, 0);
|
|||||||
* If set to 1 incoming external setpoint messages will be directly forwarded
|
* If set to 1 incoming external setpoint messages will be directly forwarded
|
||||||
* to the controllers if in offboard control mode
|
* to the controllers if in offboard control mode
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group MAVLink
|
* @group MAVLink
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1);
|
PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1);
|
||||||
|
|||||||
@@ -119,6 +119,6 @@ PARAM_DEFINE_INT32(NAV_DLL_N, 2);
|
|||||||
* airfield home
|
* airfield home
|
||||||
*
|
*
|
||||||
* @group Data Link Loss
|
* @group Data Link Loss
|
||||||
* @unit boolean
|
* @boolean
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(NAV_DLL_CHSK, 0);
|
PARAM_DEFINE_INT32(NAV_DLL_CHSK, 0);
|
||||||
|
|||||||
@@ -48,14 +48,13 @@
|
|||||||
*
|
*
|
||||||
* 0 = none, 1 = warning (default), 2 = loiter, 3 = return to launch, 4 = fight termination
|
* 0 = none, 1 = warning (default), 2 = loiter, 3 = return to launch, 4 = fight termination
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 4
|
* @max 4
|
||||||
* @value 0 none
|
* @value 0 None
|
||||||
* @value 1 warning
|
* @value 1 Warning
|
||||||
* @value 2 loiter
|
* @value 2 Loiter
|
||||||
* @value 3 return
|
* @value 3 Return
|
||||||
* @value 4 terminate
|
* @value 4 Terminate
|
||||||
* @group Geofence
|
* @group Geofence
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(GF_ACTION, 1);
|
PARAM_DEFINE_INT32(GF_ACTION, 1);
|
||||||
@@ -66,7 +65,6 @@ PARAM_DEFINE_INT32(GF_ACTION, 1);
|
|||||||
* Select which altitude reference should be used
|
* Select which altitude reference should be used
|
||||||
* 0 = WGS84, 1 = AMSL
|
* 0 = WGS84, 1 = AMSL
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 1
|
* @max 1
|
||||||
* @value 0 WGS84
|
* @value 0 WGS84
|
||||||
@@ -82,7 +80,6 @@ PARAM_DEFINE_INT32(GF_ALTMODE, 0);
|
|||||||
* no dependence on the position estimator
|
* no dependence on the position estimator
|
||||||
* 0 = global position, 1 = GPS
|
* 0 = global position, 1 = GPS
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 1
|
* @max 1
|
||||||
* @value 0 GPOS
|
* @value 0 GPOS
|
||||||
|
|||||||
@@ -73,7 +73,7 @@ PARAM_DEFINE_FLOAT(MIS_LTRMIN_ALT, 1.2f);
|
|||||||
* When enabled, missions that have been uploaded by the GCS are stored
|
* When enabled, missions that have been uploaded by the GCS are stored
|
||||||
* and reloaded after reboot persistently.
|
* and reloaded after reboot persistently.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Mission
|
* @group Mission
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 1);
|
PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 1);
|
||||||
@@ -99,16 +99,10 @@ PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 900);
|
|||||||
* 1: the system will follow a first order hold altitude setpoint
|
* 1: the system will follow a first order hold altitude setpoint
|
||||||
* values follow the definition in enum mission_altitude_mode
|
* values follow the definition in enum mission_altitude_mode
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 1
|
* @max 1
|
||||||
<<<<<<< e22e0b28b61a7b4f7d10756678b8f4b533b3622e
|
|
||||||
* @value 0 Zero Order Hold
|
* @value 0 Zero Order Hold
|
||||||
* @value 1 First Order Hold
|
* @value 1 First Order Hold
|
||||||
=======
|
|
||||||
* @value 0 zero order
|
|
||||||
* @value 1 first order
|
|
||||||
>>>>>>> mission param @unit
|
|
||||||
* @group Mission
|
* @group Mission
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(MIS_ALTMODE, 1);
|
PARAM_DEFINE_INT32(MIS_ALTMODE, 1);
|
||||||
@@ -118,20 +112,12 @@ PARAM_DEFINE_INT32(MIS_ALTMODE, 1);
|
|||||||
*
|
*
|
||||||
* The values are defined in the enum mission_altitude_mode
|
* The values are defined in the enum mission_altitude_mode
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 3
|
* @max 3
|
||||||
<<<<<<< e22e0b28b61a7b4f7d10756678b8f4b533b3622e
|
|
||||||
* @value 0 Heading as set by waypoint
|
* @value 0 Heading as set by waypoint
|
||||||
* @value 1 Heading towards waypoint
|
* @value 1 Heading towards waypoint
|
||||||
* @value 2 Heading towards home
|
* @value 2 Heading towards home
|
||||||
* @value 3 Heading away from home
|
* @value 3 Heading away from home
|
||||||
=======
|
|
||||||
* @value 0 destination
|
|
||||||
* @value 1 next
|
|
||||||
* @value 2 home
|
|
||||||
* @value 3 home back
|
|
||||||
>>>>>>> mission param @unit
|
|
||||||
* @group Mission
|
* @group Mission
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(MIS_YAWMODE, 1);
|
PARAM_DEFINE_INT32(MIS_YAWMODE, 1);
|
||||||
@@ -144,9 +130,9 @@ PARAM_DEFINE_INT32(MIS_YAWMODE, 1);
|
|||||||
* Mainly useful for VTOLs that have less yaw authority and might not reach target
|
* Mainly useful for VTOLs that have less yaw authority and might not reach target
|
||||||
* yaw in wind. Disabled by default.
|
* yaw in wind. Disabled by default.
|
||||||
*
|
*
|
||||||
|
* @unit s
|
||||||
* @min -1
|
* @min -1
|
||||||
* @max 20
|
* @max 20
|
||||||
* @unit second
|
|
||||||
* @increment 1
|
* @increment 1
|
||||||
* @group Mission
|
* @group Mission
|
||||||
*/
|
*/
|
||||||
@@ -158,7 +144,6 @@ PARAM_DEFINE_FLOAT(MIS_YAW_TMT, -1.0f);
|
|||||||
* @unit deg
|
* @unit deg
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 90
|
* @max 90
|
||||||
* @unit degree
|
|
||||||
* @increment 1
|
* @increment 1
|
||||||
* @group Mission
|
* @group Mission
|
||||||
*/
|
*/
|
||||||
|
|||||||
@@ -69,7 +69,7 @@ PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 10.0f);
|
|||||||
*
|
*
|
||||||
* If set to 1 the behaviour on data link loss is set to a mode according to the Outback Challenge (OBC) rules
|
* If set to 1 the behaviour on data link loss is set to a mode according to the Outback Challenge (OBC) rules
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Mission
|
* @group Mission
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(NAV_DLL_OBC, 0);
|
PARAM_DEFINE_INT32(NAV_DLL_OBC, 0);
|
||||||
@@ -79,7 +79,7 @@ PARAM_DEFINE_INT32(NAV_DLL_OBC, 0);
|
|||||||
*
|
*
|
||||||
* If set to 1 the behaviour on data link loss is set to a mode according to the Outback Challenge (OBC) rules
|
* If set to 1 the behaviour on data link loss is set to a mode according to the Outback Challenge (OBC) rules
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Mission
|
* @group Mission
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(NAV_RCL_OBC, 0);
|
PARAM_DEFINE_INT32(NAV_RCL_OBC, 0);
|
||||||
|
|||||||
@@ -306,7 +306,7 @@ PARAM_DEFINE_FLOAT(INAV_FLOW_DIST_Y, 0.0f);
|
|||||||
*
|
*
|
||||||
* Disable mocap
|
* Disable mocap
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Position Estimator INAV
|
* @group Position Estimator INAV
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(INAV_DISAB_MOCAP, 0);
|
PARAM_DEFINE_FLOAT(INAV_DISAB_MOCAP, 0);
|
||||||
@@ -316,7 +316,7 @@ PARAM_DEFINE_FLOAT(INAV_DISAB_MOCAP, 0);
|
|||||||
*
|
*
|
||||||
* Enable LIDAR for altitude estimation
|
* Enable LIDAR for altitude estimation
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Position Estimator INAV
|
* @group Position Estimator INAV
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(INAV_LIDAR_EST, 0);
|
PARAM_DEFINE_FLOAT(INAV_LIDAR_EST, 0);
|
||||||
@@ -352,7 +352,7 @@ PARAM_DEFINE_INT32(CBRK_NO_VISION, 0);
|
|||||||
* Else the system uses the combined attitude / position
|
* Else the system uses the combined attitude / position
|
||||||
* filter framework.
|
* filter framework.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Position Estimator INAV
|
* @group Position Estimator INAV
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(INAV_ENABLED, 1);
|
PARAM_DEFINE_INT32(INAV_ENABLED, 1);
|
||||||
|
|||||||
@@ -56,12 +56,11 @@ PARAM_DEFINE_INT32(SDLOG_RATE, -1);
|
|||||||
* parameter is only read out before logging starts
|
* parameter is only read out before logging starts
|
||||||
* (which commonly is before arming).
|
* (which commonly is before arming).
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min -1
|
* @min -1
|
||||||
* @max 1
|
* @max 1
|
||||||
* @value -1 command line
|
* @value -1 Command Line
|
||||||
* @value 0 disable
|
* @value 0 Disable
|
||||||
* @value 1 enable
|
* @value 1 Enable
|
||||||
* @group SD Logging
|
* @group SD Logging
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(SDLOG_EXT, -1);
|
PARAM_DEFINE_INT32(SDLOG_EXT, -1);
|
||||||
@@ -73,7 +72,7 @@ PARAM_DEFINE_INT32(SDLOG_EXT, -1);
|
|||||||
* to only use the time stamp if a 3D GPS lock is
|
* to only use the time stamp if a 3D GPS lock is
|
||||||
* present.
|
* present.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group SD Logging
|
* @group SD Logging
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(SDLOG_GPSTIME, 1);
|
PARAM_DEFINE_INT32(SDLOG_GPSTIME, 1);
|
||||||
|
|||||||
@@ -329,7 +329,6 @@ PARAM_DEFINE_INT32(CAL_MAG1_ID, 0);
|
|||||||
* should only attempt to configure the rotation if the value is
|
* should only attempt to configure the rotation if the value is
|
||||||
* greater than or equal to zero.
|
* greater than or equal to zero.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value -1 Internal mag
|
* @value -1 Internal mag
|
||||||
* @value 0 No rotation
|
* @value 0 No rotation
|
||||||
* @value 1 Yaw 45°
|
* @value 1 Yaw 45°
|
||||||
@@ -536,7 +535,6 @@ PARAM_DEFINE_INT32(CAL_MAG2_ID, 0);
|
|||||||
* should only attempt to configure the rotation if the value is
|
* should only attempt to configure the rotation if the value is
|
||||||
* greater than or equal to zero.
|
* greater than or equal to zero.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value -1 Internal mag
|
* @value -1 Internal mag
|
||||||
* @value 0 No rotation
|
* @value 0 No rotation
|
||||||
* @value 1 Yaw 45°
|
* @value 1 Yaw 45°
|
||||||
@@ -735,7 +733,6 @@ PARAM_DEFINE_FLOAT(SENS_BARO_QNH, 1013.25f);
|
|||||||
*
|
*
|
||||||
* This parameter defines the rotation of the FMU board relative to the platform.
|
* This parameter defines the rotation of the FMU board relative to the platform.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value 0 No rotation
|
* @value 0 No rotation
|
||||||
* @value 1 Yaw 45°
|
* @value 1 Yaw 45°
|
||||||
* @value 2 Yaw 90°
|
* @value 2 Yaw 90°
|
||||||
@@ -773,7 +770,6 @@ PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0);
|
|||||||
* This parameter defines the rotation of the PX4FLOW board relative to the platform.
|
* This parameter defines the rotation of the PX4FLOW board relative to the platform.
|
||||||
* Zero rotation is defined as Y on flow board pointing towards front of vehicle
|
* Zero rotation is defined as Y on flow board pointing towards front of vehicle
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value 0 No rotation
|
* @value 0 No rotation
|
||||||
* @value 1 Yaw 45°
|
* @value 1 Yaw 45°
|
||||||
* @value 2 Yaw 90°
|
* @value 2 Yaw 90°
|
||||||
@@ -825,7 +821,6 @@ PARAM_DEFINE_FLOAT(SENS_BOARD_Z_OFF, 0.0f);
|
|||||||
/**
|
/**
|
||||||
* External magnetometer rotation
|
* External magnetometer rotation
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value 0 No rotation
|
* @value 0 No rotation
|
||||||
* @value 1 Yaw 45°
|
* @value 1 Yaw 45°
|
||||||
* @value 2 Yaw 90°
|
* @value 2 Yaw 90°
|
||||||
@@ -860,7 +855,6 @@ PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0);
|
|||||||
/**
|
/**
|
||||||
* Select primary magnetometer
|
* Select primary magnetometer
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 2
|
* @max 2
|
||||||
* @value 0 Auto-select Mag
|
* @value 0 Auto-select Mag
|
||||||
@@ -1921,7 +1915,6 @@ PARAM_DEFINE_FLOAT(RC18_DZ, 0.0f);
|
|||||||
/**
|
/**
|
||||||
* Enable relay control of relay 1 mapped to the Spektrum receiver power supply
|
* Enable relay control of relay 1 mapped to the Spektrum receiver power supply
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 1
|
* @max 1
|
||||||
* @value 0 Disabled
|
* @value 0 Disabled
|
||||||
@@ -1933,7 +1926,6 @@ PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */
|
|||||||
/**
|
/**
|
||||||
* DSM binding trigger.
|
* DSM binding trigger.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value -1 Inactive
|
* @value -1 Inactive
|
||||||
* @value 0 Start DSM2 bind
|
* @value 0 Start DSM2 bind
|
||||||
* @value 1 Start DSMX bind
|
* @value 1 Start DSMX bind
|
||||||
@@ -1992,7 +1984,7 @@ PARAM_DEFINE_INT32(RC_CHAN_CNT, 0);
|
|||||||
* indicates that the threshold value where automatically set by the ground
|
* indicates that the threshold value where automatically set by the ground
|
||||||
* station software. It is only meant for ground station use.
|
* station software. It is only meant for ground station use.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Radio Calibration
|
* @group Radio Calibration
|
||||||
*/
|
*/
|
||||||
|
|
||||||
@@ -2005,7 +1997,6 @@ PARAM_DEFINE_INT32(RC_TH_USER, 1);
|
|||||||
* which channel should be used for reading roll inputs from.
|
* which channel should be used for reading roll inputs from.
|
||||||
* A value of zero indicates the switch is not assigned.
|
* A value of zero indicates the switch is not assigned.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @value 0 Unassigned
|
* @value 0 Unassigned
|
||||||
@@ -2038,7 +2029,6 @@ PARAM_DEFINE_INT32(RC_MAP_ROLL, 0);
|
|||||||
* which channel should be used for reading pitch inputs from.
|
* which channel should be used for reading pitch inputs from.
|
||||||
* A value of zero indicates the switch is not assigned.
|
* A value of zero indicates the switch is not assigned.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @value 0 Unassigned
|
* @value 0 Unassigned
|
||||||
@@ -2071,7 +2061,6 @@ PARAM_DEFINE_INT32(RC_MAP_PITCH, 0);
|
|||||||
* If 0, whichever channel is mapped to throttle is used
|
* If 0, whichever channel is mapped to throttle is used
|
||||||
* otherwise the value indicates the specific rc channel to use
|
* otherwise the value indicates the specific rc channel to use
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @value 0 Unassigned
|
* @value 0 Unassigned
|
||||||
@@ -2103,7 +2092,6 @@ PARAM_DEFINE_INT32(RC_MAP_FAILSAFE, 0); //Default to throttle function
|
|||||||
* which channel should be used for reading throttle inputs from.
|
* which channel should be used for reading throttle inputs from.
|
||||||
* A value of zero indicates the switch is not assigned.
|
* A value of zero indicates the switch is not assigned.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @value 0 Unassigned
|
* @value 0 Unassigned
|
||||||
@@ -2136,7 +2124,6 @@ PARAM_DEFINE_INT32(RC_MAP_THROTTLE, 0);
|
|||||||
* which channel should be used for reading yaw inputs from.
|
* which channel should be used for reading yaw inputs from.
|
||||||
* A value of zero indicates the switch is not assigned.
|
* A value of zero indicates the switch is not assigned.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @value 0 Unassigned
|
* @value 0 Unassigned
|
||||||
@@ -2168,7 +2155,6 @@ PARAM_DEFINE_INT32(RC_MAP_YAW, 0);
|
|||||||
* If this parameter is non-zero, flight modes are only selected
|
* If this parameter is non-zero, flight modes are only selected
|
||||||
* by this channel and are assigned to six slots.
|
* by this channel and are assigned to six slots.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Switches
|
* @group Radio Switches
|
||||||
@@ -2202,7 +2188,6 @@ PARAM_DEFINE_INT32(RC_MAP_FLTMODE, 0);
|
|||||||
* which channel should be used for deciding about the main mode.
|
* which channel should be used for deciding about the main mode.
|
||||||
* A value of zero indicates the switch is not assigned.
|
* A value of zero indicates the switch is not assigned.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Switches
|
* @group Radio Switches
|
||||||
@@ -2231,7 +2216,6 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0);
|
|||||||
/**
|
/**
|
||||||
* Return switch channel
|
* Return switch channel
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Switches
|
* @group Radio Switches
|
||||||
@@ -2260,7 +2244,6 @@ PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
|
|||||||
/**
|
/**
|
||||||
* Rattitude switch channel
|
* Rattitude switch channel
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Switches
|
* @group Radio Switches
|
||||||
@@ -2289,7 +2272,6 @@ PARAM_DEFINE_INT32(RC_MAP_RATT_SW, 0);
|
|||||||
/**
|
/**
|
||||||
* Position Control switch channel
|
* Position Control switch channel
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Switches
|
* @group Radio Switches
|
||||||
@@ -2318,7 +2300,6 @@ PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0);
|
|||||||
/**
|
/**
|
||||||
* Loiter switch channel
|
* Loiter switch channel
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Switches
|
* @group Radio Switches
|
||||||
@@ -2347,7 +2328,6 @@ PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0);
|
|||||||
/**
|
/**
|
||||||
* Acro switch channel
|
* Acro switch channel
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Switches
|
* @group Radio Switches
|
||||||
@@ -2376,7 +2356,6 @@ PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0);
|
|||||||
/**
|
/**
|
||||||
* Offboard switch channel
|
* Offboard switch channel
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Switches
|
* @group Radio Switches
|
||||||
@@ -2405,7 +2384,6 @@ PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
|
|||||||
/**
|
/**
|
||||||
* Kill switch channel
|
* Kill switch channel
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Switches
|
* @group Radio Switches
|
||||||
@@ -2434,7 +2412,6 @@ PARAM_DEFINE_INT32(RC_MAP_KILL_SW, 0);
|
|||||||
/**
|
/**
|
||||||
* Flaps channel
|
* Flaps channel
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Switches
|
* @group Radio Switches
|
||||||
@@ -2465,7 +2442,6 @@ PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0);
|
|||||||
*
|
*
|
||||||
* Default function: Camera pitch
|
* Default function: Camera pitch
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Calibration
|
* @group Radio Calibration
|
||||||
@@ -2496,7 +2472,6 @@ PARAM_DEFINE_INT32(RC_MAP_AUX1, 0);
|
|||||||
*
|
*
|
||||||
* Default function: Camera roll
|
* Default function: Camera roll
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Calibration
|
* @group Radio Calibration
|
||||||
@@ -2527,7 +2502,6 @@ PARAM_DEFINE_INT32(RC_MAP_AUX2, 0);
|
|||||||
*
|
*
|
||||||
* Default function: Camera azimuth / yaw
|
* Default function: Camera azimuth / yaw
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Calibration
|
* @group Radio Calibration
|
||||||
@@ -2559,7 +2533,6 @@ PARAM_DEFINE_INT32(RC_MAP_AUX3, 0);
|
|||||||
* Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel.
|
* Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel.
|
||||||
* Set to 0 to deactivate *
|
* Set to 0 to deactivate *
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Calibration
|
* @group Radio Calibration
|
||||||
@@ -2591,7 +2564,6 @@ PARAM_DEFINE_INT32(RC_MAP_PARAM1, 0);
|
|||||||
* Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel.
|
* Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel.
|
||||||
* Set to 0 to deactivate *
|
* Set to 0 to deactivate *
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Calibration
|
* @group Radio Calibration
|
||||||
@@ -2623,7 +2595,6 @@ PARAM_DEFINE_INT32(RC_MAP_PARAM2, 0);
|
|||||||
* Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel.
|
* Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel.
|
||||||
* Set to 0 to deactivate *
|
* Set to 0 to deactivate *
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Calibration
|
* @group Radio Calibration
|
||||||
@@ -2832,7 +2803,6 @@ PARAM_DEFINE_FLOAT(RC_KILLSWITCH_TH, 0.25f);
|
|||||||
*
|
*
|
||||||
* Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.
|
* Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 18
|
* @max 18
|
||||||
* @value 0 Unassigned
|
* @value 0 Unassigned
|
||||||
@@ -2888,7 +2858,7 @@ PARAM_DEFINE_INT32(RC_RSSI_PWM_MIN, 2000);
|
|||||||
*
|
*
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group Sensor Enable
|
* @group Sensor Enable
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(SENS_EN_LL40LS, 0);
|
PARAM_DEFINE_INT32(SENS_EN_LL40LS, 0);
|
||||||
|
|||||||
@@ -90,7 +90,6 @@ PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2);
|
|||||||
* 921600: enables onboard mode at 921600 baud, 8N1. 57600: enables onboard mode at 57600 baud, 8N1.
|
* 921600: enables onboard mode at 921600 baud, 8N1. 57600: enables onboard mode at 57600 baud, 8N1.
|
||||||
* 157600: enables OSD mode at 57600 baud, 8N1.
|
* 157600: enables OSD mode at 57600 baud, 8N1.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value 921600 Companion Link (921600 baud, 8N1)
|
* @value 921600 Companion Link (921600 baud, 8N1)
|
||||||
* @value 57600 Companion Link (57600 baud, 8N1)
|
* @value 57600 Companion Link (57600 baud, 8N1)
|
||||||
* @value 157600 OSD (57600 baud, 8N1)
|
* @value 157600 OSD (57600 baud, 8N1)
|
||||||
|
|||||||
@@ -47,13 +47,12 @@
|
|||||||
* 2 - Enabled support for dynamic node ID allocation and firmware update.
|
* 2 - Enabled support for dynamic node ID allocation and firmware update.
|
||||||
* 3 - Sets the motor control outputs to UAVCAN and enables support for dynamic node ID allocation and firmware update.
|
* 3 - Sets the motor control outputs to UAVCAN and enables support for dynamic node ID allocation and firmware update.
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @min 0
|
* @min 0
|
||||||
* @max 3
|
* @max 3
|
||||||
* @value 0 disabled
|
* @value 0 Disabled
|
||||||
* @value 1 enabled
|
* @value 1 Enabled
|
||||||
* @value 2 update
|
* @value 2 Dynamic ID/Update
|
||||||
* @value 3 motors/update
|
* @value 3 Motors/Update
|
||||||
* @group UAVCAN
|
* @group UAVCAN
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(UAVCAN_ENABLE, 0);
|
PARAM_DEFINE_INT32(UAVCAN_ENABLE, 0);
|
||||||
|
|||||||
@@ -110,7 +110,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM, 10.0f);
|
|||||||
* If set to one this parameter will cause permanent attitude stabilization in fw mode.
|
* If set to one this parameter will cause permanent attitude stabilization in fw mode.
|
||||||
* This parameter has been introduced for pure convenience sake.
|
* This parameter has been introduced for pure convenience sake.
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group VTOL Attitude Control
|
* @group VTOL Attitude Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(VT_FW_PERM_STAB, 0);
|
PARAM_DEFINE_INT32(VT_FW_PERM_STAB, 0);
|
||||||
@@ -172,7 +172,6 @@ PARAM_DEFINE_FLOAT(VT_ARSP_LP_GAIN, 0.3f);
|
|||||||
/**
|
/**
|
||||||
* VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)
|
* VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)
|
||||||
*
|
*
|
||||||
* @unit enum
|
|
||||||
* @value 0 Tailsitter
|
* @value 0 Tailsitter
|
||||||
* @value 1 Tiltrotor
|
* @value 1 Tiltrotor
|
||||||
* @value 2 Standard
|
* @value 2 Standard
|
||||||
@@ -188,7 +187,7 @@ PARAM_DEFINE_INT32(VT_TYPE, 0);
|
|||||||
*
|
*
|
||||||
* If set to 1 the elevons are locked in multicopter mode
|
* If set to 1 the elevons are locked in multicopter mode
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group VTOL Attitude Control
|
* @group VTOL Attitude Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(VT_ELEV_MC_LOCK, 0);
|
PARAM_DEFINE_INT32(VT_ELEV_MC_LOCK, 0);
|
||||||
@@ -252,7 +251,7 @@ PARAM_DEFINE_FLOAT(VT_ARSP_TRANS, 10.0f);
|
|||||||
/**
|
/**
|
||||||
* Enable optimal recovery strategy for pitch-weak tailsitters
|
* Enable optimal recovery strategy for pitch-weak tailsitters
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group VTOL Attitude Control
|
* @group VTOL Attitude Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(VT_OPT_RECOV_EN, 0);
|
PARAM_DEFINE_INT32(VT_OPT_RECOV_EN, 0);
|
||||||
@@ -260,7 +259,7 @@ PARAM_DEFINE_INT32(VT_OPT_RECOV_EN, 0);
|
|||||||
/**
|
/**
|
||||||
* Enable weather-vane mode landings for missions
|
* Enable weather-vane mode landings for missions
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group VTOL Attitude Control
|
* @group VTOL Attitude Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(VT_WV_LND_EN, 0);
|
PARAM_DEFINE_INT32(VT_WV_LND_EN, 0);
|
||||||
@@ -282,7 +281,7 @@ PARAM_DEFINE_FLOAT(VT_WV_YAWR_SCL, 0.15f);
|
|||||||
/**
|
/**
|
||||||
* Enable weather-vane mode for loiter
|
* Enable weather-vane mode for loiter
|
||||||
*
|
*
|
||||||
* @unit boolean
|
* @boolean
|
||||||
* @group VTOL Attitude Control
|
* @group VTOL Attitude Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(VT_WV_LTR_EN, 0);
|
PARAM_DEFINE_INT32(VT_WV_LTR_EN, 0);
|
||||||
|
|||||||
Reference in New Issue
Block a user