mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-28 05:04:07 +08:00
Add a lot of MAVLink parameter documentation.
This commit is contained in:
parent
ccfe476326
commit
7441efde47
@ -45,28 +45,46 @@
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/*
|
||||
* Launch detection parameters, accessible via MAVLink
|
||||
* Catapult launch detection parameters, accessible via MAVLink
|
||||
*
|
||||
*/
|
||||
|
||||
/* Catapult Launch detection */
|
||||
|
||||
// @DisplayName Switch to enable launchdetection
|
||||
// @Description if set to 1 launchdetection is enabled
|
||||
// @Range 0 or 1
|
||||
/**
|
||||
* Enable launch detection.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Launch detection
|
||||
*/
|
||||
PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);
|
||||
|
||||
// @DisplayName Catapult Accelerometer Threshold
|
||||
// @Description LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection
|
||||
// @Range > 0
|
||||
/**
|
||||
* Catapult accelerometer theshold.
|
||||
*
|
||||
* LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
|
||||
*
|
||||
* @min 0
|
||||
* @group Launch detection
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f);
|
||||
|
||||
// @DisplayName Catapult Time Threshold
|
||||
// @Description LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection
|
||||
// @Range > 0, in seconds
|
||||
/**
|
||||
* Catapult time theshold.
|
||||
*
|
||||
* LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
|
||||
*
|
||||
* @min 0
|
||||
* @group Launch detection
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(LAUN_CAT_T, 0.05f);
|
||||
|
||||
// @DisplayName Throttle setting while detecting the launch
|
||||
// @Description The throttle is set to this value while the system is waiting for the takeoff
|
||||
// @Range 0 to 1
|
||||
/**
|
||||
* Throttle setting while detecting launch.
|
||||
*
|
||||
* The throttle is set to this value while the system is waiting for the take-off.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Launch detection
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(LAUN_THR_PRE, 0.0f);
|
||||
|
||||
@ -48,7 +48,39 @@
|
||||
PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
|
||||
|
||||
/**
|
||||
* Empty cell voltage.
|
||||
*
|
||||
* Defines the voltage where a single cell of the battery is considered empty.
|
||||
*
|
||||
* @group Battery Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f);
|
||||
|
||||
/**
|
||||
* Full cell voltage.
|
||||
*
|
||||
* Defines the voltage where a single cell of the battery is considered full.
|
||||
*
|
||||
* @group Battery Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BAT_V_FULL, 3.9f);
|
||||
|
||||
/**
|
||||
* Number of cells.
|
||||
*
|
||||
* Defines the number of cells the attached battery consists of.
|
||||
*
|
||||
* @group Battery Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(BAT_N_CELLS, 3);
|
||||
|
||||
/**
|
||||
* Battery capacity.
|
||||
*
|
||||
* Defines the capacity of the attached battery.
|
||||
*
|
||||
* @group Battery Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f);
|
||||
|
||||
@ -76,8 +76,20 @@
|
||||
#include <uORB/topics/mission_result.h>
|
||||
|
||||
/* define MAVLink specific parameters */
|
||||
/**
|
||||
* MAVLink system ID
|
||||
* @group MAVLink
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MAV_SYS_ID, 1);
|
||||
/**
|
||||
* MAVLink component ID
|
||||
* @group MAVLink
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MAV_COMP_ID, 50);
|
||||
/**
|
||||
* MAVLink type
|
||||
* @group MAVLink
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING);
|
||||
|
||||
__EXPORT int mavlink_main(int argc, char *argv[]);
|
||||
|
||||
@ -45,11 +45,17 @@
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/*
|
||||
* geofence parameters, accessible via MAVLink
|
||||
*
|
||||
* Geofence parameters, accessible via MAVLink
|
||||
*/
|
||||
|
||||
// @DisplayName Switch to enable geofence
|
||||
// @Description if set to 1 geofence is enabled, defaults to 1 because geofence is only enabled when the geofence.txt file is present
|
||||
// @Range 0 or 1
|
||||
/**
|
||||
* Enable geofence.
|
||||
*
|
||||
* Set to 1 to enable geofence.
|
||||
* Defaults to 1 because geofence is only enabled when the geofence.txt file is present.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Geofence
|
||||
*/
|
||||
PARAM_DEFINE_INT32(GF_ON, 1);
|
||||
|
||||
@ -50,15 +50,72 @@
|
||||
|
||||
/*
|
||||
* Navigator parameters, accessible via MAVLink
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Minimum altitude
|
||||
*
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f);
|
||||
|
||||
/**
|
||||
* Waypoint acceptance radius.
|
||||
*
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f);
|
||||
|
||||
/**
|
||||
* Loiter radius.
|
||||
*
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
|
||||
|
||||
/**
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0);
|
||||
|
||||
/**
|
||||
* Default take-off altitude.
|
||||
*
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); // default TAKEOFF altitude
|
||||
|
||||
/**
|
||||
* Landing altitude.
|
||||
*
|
||||
* Slowly descend from this altitude when landing.
|
||||
*
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing
|
||||
|
||||
/**
|
||||
* Return-to-land altitude.
|
||||
*
|
||||
* Minimum altitude for going home in RTL mode.
|
||||
*
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); // min altitude for going home in RTL mode
|
||||
PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f); // delay after descend before landing, if set to -1 the system will not land but loiter at NAV_LAND_ALT
|
||||
PARAM_DEFINE_INT32(NAV_PARACHUTE_EN, 0); // enable parachute deployment
|
||||
|
||||
/**
|
||||
* Return-to-land delay.
|
||||
*
|
||||
* Delay after descend before landing.
|
||||
* If set to -1 the system will not land but loiter at NAV_LAND_ALT.
|
||||
*
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f);
|
||||
|
||||
/**
|
||||
* Enable parachute deployment.
|
||||
*
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_PARACHUTE_EN, 0);
|
||||
|
||||
@ -42,13 +42,10 @@
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/**
|
||||
* Gyro X offset
|
||||
*
|
||||
* This is an X-axis offset for the gyro. Adjust it according to the calibration data.
|
||||
* Gyro X-axis offset
|
||||
*
|
||||
* @min -10.0
|
||||
* @max 10.0
|
||||
@ -57,7 +54,7 @@
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y offset
|
||||
* Gyro Y-axis offset
|
||||
*
|
||||
* @min -10.0
|
||||
* @max 10.0
|
||||
@ -66,7 +63,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z offset
|
||||
* Gyro Z-axis offset
|
||||
*
|
||||
* @min -5.0
|
||||
* @max 5.0
|
||||
@ -75,9 +72,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro X scaling
|
||||
*
|
||||
* X-axis scaling.
|
||||
* Gyro X-axis scaling factor
|
||||
*
|
||||
* @min -1.5
|
||||
* @max 1.5
|
||||
@ -86,9 +81,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y scaling
|
||||
*
|
||||
* Y-axis scaling.
|
||||
* Gyro Y-axis scaling factor
|
||||
*
|
||||
* @min -1.5
|
||||
* @max 1.5
|
||||
@ -97,9 +90,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z scaling
|
||||
*
|
||||
* Z-axis scaling.
|
||||
* Gyro Z-axis scaling factor
|
||||
*
|
||||
* @min -1.5
|
||||
* @max 1.5
|
||||
@ -107,10 +98,9 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f);
|
||||
|
||||
|
||||
/**
|
||||
* Magnetometer X offset
|
||||
*
|
||||
* This is an X-axis offset for the magnetometer.
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
@ -119,9 +109,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y offset
|
||||
*
|
||||
* This is an Y-axis offset for the magnetometer.
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
@ -130,9 +118,7 @@ PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z offset
|
||||
*
|
||||
* This is an Z-axis offset for the magnetometer.
|
||||
* Magnetometer Z-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
@ -140,24 +126,134 @@ PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_ZSCALE, 1.0f);
|
||||
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f);
|
||||
|
||||
|
||||
/**
|
||||
* Differential pressure sensor offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Differential pressure sensor analog enabled
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_DPRES_ANA, 0);
|
||||
|
||||
|
||||
/**
|
||||
* Board rotation
|
||||
*
|
||||
* This parameter defines the rotation of the FMU board relative to the platform.
|
||||
* Possible values are:
|
||||
* 0 = No rotation
|
||||
* 1 = Yaw 45°
|
||||
* 2 = Yaw 90°
|
||||
* 3 = Yaw 135°
|
||||
* 4 = Yaw 180°
|
||||
* 5 = Yaw 225°
|
||||
* 6 = Yaw 270°
|
||||
* 7 = Yaw 315°
|
||||
* 8 = Roll 180°
|
||||
* 9 = Roll 180°, Yaw 45°
|
||||
* 10 = Roll 180°, Yaw 90°
|
||||
* 11 = Roll 180°, Yaw 135°
|
||||
* 12 = Pitch 180°
|
||||
* 13 = Roll 180°, Yaw 225°
|
||||
* 14 = Roll 180°, Yaw 270°
|
||||
* 15 = Roll 180°, Yaw 315°
|
||||
* 16 = Roll 90°
|
||||
* 17 = Roll 90°, Yaw 45°
|
||||
* 18 = Roll 90°, Yaw 90°
|
||||
* 19 = Roll 90°, Yaw 135°
|
||||
* 20 = Roll 270°
|
||||
* 21 = Roll 270°, Yaw 45°
|
||||
* 22 = Roll 270°, Yaw 90°
|
||||
* 23 = Roll 270°, Yaw 135°
|
||||
* 24 = Pitch 90°
|
||||
* 25 = Pitch 270°
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0);
|
||||
|
||||
/**
|
||||
* External magnetometer rotation
|
||||
*
|
||||
* This parameter defines the rotation of the external magnetometer relative
|
||||
* to the platform (not relative to the FMU).
|
||||
* See SENS_BOARD_ROT for possible values.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0);
|
||||
|
||||
|
||||
/**
|
||||
* RC Channel 1 Minimum
|
||||
*
|
||||
@ -367,20 +463,52 @@ PARAM_DEFINE_FLOAT(RC18_DZ, 0.0f);
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */
|
||||
#endif
|
||||
PARAM_DEFINE_INT32(RC_DSM_BIND, -1); /* -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind */
|
||||
|
||||
/**
|
||||
* DSM binding trigger.
|
||||
*
|
||||
* -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind
|
||||
*
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_DSM_BIND, -1);
|
||||
|
||||
|
||||
/**
|
||||
* Scaling factor for battery voltage sensor on PX4IO.
|
||||
*
|
||||
* @group Battery Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(BAT_V_SCALE_IO, 10000);
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
/**
|
||||
* Scaling factor for battery voltage sensor on FMU v2.
|
||||
*
|
||||
* @group Battery Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f);
|
||||
#else
|
||||
/* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */
|
||||
/* PX4IOAR: 0.00838095238 */
|
||||
/* FMU standalone: 1/(10 / (47+10)) * (3.3 / 4095) = 0.00459340659 */
|
||||
/* FMU with PX4IOAR: (3.3f * 52.0f / 5.0f / 4095.0f) */
|
||||
/**
|
||||
* Scaling factor for battery voltage sensor on FMU v1.
|
||||
*
|
||||
* FMUv1 standalone: 1/(10 / (47+10)) * (3.3 / 4095) = 0.00459340659
|
||||
* FMUv1 with PX4IO: 0.00459340659
|
||||
* FMUv1 with PX4IOAR: (3.3f * 52.0f / 5.0f / 4095.0f) = 0.00838095238
|
||||
*
|
||||
* @group Battery Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.00459340659f);
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Scaling factor for battery current sensor.
|
||||
*
|
||||
* @group Battery Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BAT_C_SCALING, 0.0124); /* scaling for 3DR power brick */
|
||||
|
||||
|
||||
/**
|
||||
* Roll control channel mapping.
|
||||
*
|
||||
@ -446,22 +574,127 @@ PARAM_DEFINE_INT32(RC_MAP_YAW, 4);
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0);
|
||||
|
||||
/**
|
||||
* Return switch channel mapping.
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
|
||||
|
||||
/**
|
||||
* Assist switch channel mapping.
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0);
|
||||
|
||||
/**
|
||||
* Mission switch channel mapping.
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0);
|
||||
|
||||
//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
|
||||
|
||||
/**
|
||||
* Flaps channel mapping.
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0);
|
||||
|
||||
PARAM_DEFINE_INT32(RC_MAP_AUX1, 0); /**< default function: camera pitch */
|
||||
PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera roll */
|
||||
PARAM_DEFINE_INT32(RC_MAP_AUX3, 0); /**< default function: camera azimuth / yaw */
|
||||
/**
|
||||
* Auxiliary switch 1 channel mapping.
|
||||
*
|
||||
* Default function: Camera pitch
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_AUX1, 0);
|
||||
|
||||
/**
|
||||
* Auxiliary switch 2 channel mapping.
|
||||
*
|
||||
* Default function: Camera roll
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera roll */
|
||||
|
||||
/**
|
||||
* Auxiliary switch 3 channel mapping.
|
||||
*
|
||||
* Default function: Camera azimuth / yaw
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_AUX3, 0);
|
||||
|
||||
|
||||
/**
|
||||
* Roll scaling factor
|
||||
*
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_SCALE_ROLL, 0.6f);
|
||||
|
||||
/**
|
||||
* Pitch scaling factor
|
||||
*
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_SCALE_PITCH, 0.6f);
|
||||
|
||||
/**
|
||||
* Yaw scaling factor
|
||||
*
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 2.0f);
|
||||
|
||||
PARAM_DEFINE_INT32(RC_FS_CH, 0); /**< RC failsafe channel, 0 = disable */
|
||||
PARAM_DEFINE_INT32(RC_FS_MODE, 0); /**< RC failsafe mode: 0 = too low means signal loss, 1 = too high means signal loss */
|
||||
PARAM_DEFINE_FLOAT(RC_FS_THR, 800); /**< RC failsafe PWM threshold */
|
||||
|
||||
/**
|
||||
* Failsafe channel mapping.
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_FS_CH, 0);
|
||||
|
||||
/**
|
||||
* Failsafe channel mode.
|
||||
*
|
||||
* 0 = too low means signal loss,
|
||||
* 1 = too high means signal loss
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_FS_MODE, 0);
|
||||
|
||||
/**
|
||||
* Failsafe channel PWM threshold.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_FS_THR, 800);
|
||||
|
||||
@ -40,8 +40,23 @@
|
||||
#include <nuttx/config.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
// Auto-start script with index #n
|
||||
/**
|
||||
* Auto-start script index.
|
||||
*
|
||||
* Defines the auto-start script used to bootstrap the system.
|
||||
*
|
||||
* @group System
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SYS_AUTOSTART, 0);
|
||||
|
||||
// Automatically configure default values
|
||||
/**
|
||||
* Automatically configure default values.
|
||||
*
|
||||
* Set to 1 to set platform-specific parameters to their default
|
||||
* values on next system startup.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group System
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user