diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps index 947e59fbac..6dc1c6b1fc 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_apps +++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps @@ -2,6 +2,8 @@ # # Standard apps for fixed wing # +# NOTE: Script variables are declared/initialized/unset in the rcS script. +# # LPE if param compare SYS_MC_EST_GROUP 1 @@ -12,22 +14,22 @@ then fi # -# Start the attitude and position estimator +# Start the attitude and position estimator. # ekf2 start # -# Start attitude controller +# Start attitude controller. # fw_att_control start fw_pos_control_l1 start # -# Start Land Detector +# Start Land Detector. # land_detector start fixedwing # -# Start Wind and Airspeed Scale Estimator +# Start Wind and Airspeed Scale Estimator. # #wind_estimator start diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 20e0b60ada..0f23d06674 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -1,11 +1,16 @@ #!nsh +# +# Fixed wing default parameters +# +# NOTE: Script variables are declared/initialized/unset in the rcS script. +# set VEHICLE_TYPE fw if [ $AUTOCNF == yes ] then # - # Default parameters for FW + # Default parameters for fixed wing uavs. # param set COM_POS_FS_DELAY 5 param set COM_POS_FS_EPH 25 @@ -23,8 +28,8 @@ then param set RTL_DESCEND_ALT 100 param set RTL_LAND_DELAY -1 - # FW uses L1 distance for acceptance radius - # set a smaller NAV_ACC_RAD for vertical acceptance distance + # FW uses L1 distance for acceptance radius, + # set a smaller NAV_ACC_RAD for vertical acceptance distance. param set NAV_ACC_RAD 10 param set MIS_LTRMIN_ALT 25 @@ -32,11 +37,11 @@ then param set PWM_RATE 50 - # FW takeoff acceleration can easily exceed ublox GPS 2G default + # FW takeoff acceleration can easily exceed ublox GPS 2G default. param set GPS_UBX_DYNMODEL 8 fi -# This is the gimbal pass mixer +# This is the gimbal pass mixer. set MIXER_AUX pass set PWM_AUX_RATE 50 set PWM_AUX_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_apps b/ROMFS/px4fmu_common/init.d/rc.mc_apps index 59bb59b0a9..7650e117ee 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_apps +++ b/ROMFS/px4fmu_common/init.d/rc.mc_apps @@ -1,14 +1,14 @@ #!nsh # -# Standard apps for multirotors: -# att & pos estimator, att & pos control. +# Standard apps for multirotors. Attitude/Position estimator, Attitude/Position control. +# +# NOTE: Script variables are declared/initialized/unset in the rcS script. # - -#--------------------------------------- -# Estimator group selction -# -# INAV (deprecated) +############################################################################### +# Begin Estimator Group Selection # +############################################################################### +# INAV (deprecated). if param compare SYS_MC_EST_GROUP 0 then echo "ERROR [init] Estimator INAV deprecated. Using EKF2" @@ -31,18 +31,26 @@ then fi fi -# EKF +# EKF2 if param compare SYS_MC_EST_GROUP 2 then ekf2 start fi -#--------------------------------------- +############################################################################### +# End Estimator Group Selection # +############################################################################### +# +# Start Multicopter Attitude Controller. +# mc_att_control start +# +# Start Multicopter Position Controller. +# mc_pos_control start # -# Start Land Detector +# Start Multicopter Land Detector. # land_detector start multicopter diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 6f04791f61..bf33c1d2e1 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -1,20 +1,26 @@ #!nsh +# +# Multicopter default parameters. +# +# NOTE: Script variables are declared/initialized/unset in the rcS script. +# set VEHICLE_TYPE mc if [ $AUTOCNF == yes ] then param set NAV_ACC_RAD 2.0 + param set RTL_RETURN_ALT 30.0 param set RTL_DESCEND_ALT 10.0 - param set PWM_MIN 1075 - param set PWM_MAX 1950 - param set PWM_RATE 400 - param set RTL_LAND_DELAY 0 + + param set PWM_MAX 1950 + param set PWM_MIN 1075 + param set PWM_RATE 400 fi -# This is the gimbal pass mixer +# This is the gimbal pass mixer. set MIXER_AUX pass set PWM_AUX_RATE 50 set PWM_AUX_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/rc.ugv_apps b/ROMFS/px4fmu_common/init.d/rc.ugv_apps index 17c566ee04..8c7766c516 100644 --- a/ROMFS/px4fmu_common/init.d/rc.ugv_apps +++ b/ROMFS/px4fmu_common/init.d/rc.ugv_apps @@ -1,10 +1,12 @@ #!nsh # -# Standard apps for unmanned ground vehicles (UGV) +# Standard apps for unmanned ground vehicles (UGV). +# +# NOTE: Script variables are declared/initialized/unset in the rcS script. # # -# Start the attitude and position estimator +# Start the attitude and position estimator. # ekf2 start #attitude_estimator_q start @@ -12,13 +14,13 @@ ekf2 start # -# Start attitude controllers +# Start attitude controllers. # gnd_att_control start gnd_pos_control start # -# Start Land Detector +# Start Land Detector. # land_detector start ugv diff --git a/ROMFS/px4fmu_common/init.d/rc.ugv_defaults b/ROMFS/px4fmu_common/init.d/rc.ugv_defaults index 1af7920217..53a6b4603f 100644 --- a/ROMFS/px4fmu_common/init.d/rc.ugv_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.ugv_defaults @@ -1,4 +1,9 @@ #!nsh +# +# UGV default parameters. +# +# NOTE: Script variables are declared/initialized/unset in the rcS script. +# set VEHICLE_TYPE ugv @@ -7,14 +12,14 @@ then # # Default parameters for UGVs # + param set MIS_LTRMIN_ALT 0.01 + param set MIS_TAKEOFF_ALT 0.01 + param set NAV_DLL_ACT 0 param set NAV_ACC_RAD 2.0 # temporary param set NAV_FW_ALT_RAD 1000 - - param set MIS_LTRMIN_ALT 0.01 - param set MIS_TAKEOFF_ALT 0.01 fi # Enable servo output on pins 3 and 4 (steering and thrust) diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_apps b/ROMFS/px4fmu_common/init.d/rc.vtol_apps index 6fa43551ea..00e79abfbf 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_apps +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_apps @@ -1,14 +1,14 @@ #!nsh # -# Standard apps for vtol: -# att & pos estimator, att & pos control. +# Standard apps for vtol: Attitude/Position estimator, Attitude/Position control. # +# NOTE: Script variables are declared/initialized/unset in the rcS script. # +############################################################################### +# Begin Estimator group selection # +############################################################################### -#--------------------------------------- -# Estimator group selction -# # INAV (deprecated) if param compare SYS_MC_EST_GROUP 0 then @@ -37,7 +37,10 @@ if param compare SYS_MC_EST_GROUP 2 then ekf2 start fi -#--------------------------------------- + +############################################################################### +# End Estimator group selection # +############################################################################### vtol_att_control start diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index 9576c898e6..b6bf21dfd4 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -1,4 +1,9 @@ #!nsh +# +# VTOL default parameters. +# +# NOTE: Script variables are declared/initialized/unset in the rcS script. +# set VEHICLE_TYPE vtol @@ -18,5 +23,5 @@ then param set RTL_LAND_DELAY 0 fi -# set environment variables (!= parameters) +# Set environment variables (!= parameters) set PWM_RATE 400 diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index f38330cd83..74a9e8742a 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -129,10 +129,14 @@ then # uorb start + # # Start tone driver + # tone_alarm start + # # play startup tone + # tune_control play -t 1 #