diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1020_uuv_generic b/ROMFS/px4fmu_common/init.d-posix/airframes/1020_uuv_generic index 2bbee570f6..77580fb1a6 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1020_uuv_generic +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1020_uuv_generic @@ -8,8 +8,5 @@ # disable circuit breaker for airspeed sensor param set-default CBRK_AIRSPD_CHK 162128 -set MAV_TYPE 12 -param set MAV_TYPE ${MAV_TYPE} - set MIXER_FILE etc/mixers-sitl/uuv_x_sitl.main.mix set MIXER custom diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1021_uuv_hippocampus b/ROMFS/px4fmu_common/init.d-posix/airframes/1021_uuv_hippocampus index 0ed6c2ed6a..d4bf9a22fc 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1021_uuv_hippocampus +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1021_uuv_hippocampus @@ -8,8 +8,5 @@ # disable circuit breaker for airspeed sensor param set-default CBRK_AIRSPD_CHK 162128 -set MAV_TYPE 12 -param set MAV_TYPE ${MAV_TYPE} - set MIXER_FILE etc/mixers-sitl/uuv_x_sitl.main.mix set MIXER custom diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy b/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy index 116f08cc24..d224008464 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy @@ -67,4 +67,3 @@ param set-default PWM_MAIN_FUNC7 107 param set-default PWM_MAIN_FUNC8 108 set MIXER skip - diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol index aa5c45dfab..472f9db832 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol @@ -80,7 +80,5 @@ param set-default VT_FW_MOT_OFFID 1234 param set-default VT_B_TRANS_DUR 8 param set-default VT_TYPE 2 -set MAV_TYPE 22 - set MIXER_FILE etc/mixers-sitl/standard_vtol_sitl.main.mix set MIXER custom diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter index 68cd393073..163e515ebb 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter @@ -7,6 +7,8 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-default MAV_TYPE 20 + # param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 4 @@ -78,7 +80,5 @@ param set-default VT_TYPE 0 param set-default WV_EN 0 -set MAV_TYPE 20 - set MIXER_FILE etc/mixers-sitl/quad_x_vtol.main.mix set MIXER custom diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor b/ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor index 7f43eddf6c..cd6d471e86 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor @@ -7,6 +7,8 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-default MAV_TYPE 21 + # param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 3 @@ -88,7 +90,5 @@ param set-default VT_MOT_ID 1234 param set-default VT_TILT_TRANS 0.6 param set-default VT_TYPE 1 -set MAV_TYPE 21 - set MIXER_FILE etc/mixers-sitl/tiltrotor_sitl.main.mix set MIXER custom diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1043_standard_vtol_drop b/ROMFS/px4fmu_common/init.d-posix/airframes/1043_standard_vtol_drop index 803d4e16d7..2a1a974587 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1043_standard_vtol_drop +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1043_standard_vtol_drop @@ -51,7 +51,5 @@ param set-default RC_MAP_AUX1 8 param set-default RC_MAP_AUX2 9 param set-default RC_MAP_AUX3 10 -set MAV_TYPE 22 - set MIXER_FILE etc/mixers-sitl/standard_vtol_sitl.main.mix set MIXER custom diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover index e8f68f70b9..ad1727bb33 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover @@ -37,6 +37,4 @@ param set-default PWM_MAIN_FUNC2 201 param set-default PWM_MAIN_FUNC6 101 param set-default PWM_MAIN_FUNC7 101 -set MAV_TYPE 10 - set MIXER_FILE skip diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover index 3773e6e3d0..2be17c1262 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover @@ -37,6 +37,4 @@ param set-default PWM_MAIN_FUNC2 101 param set-default PWM_MAIN_FUNC6 102 param set-default PWM_MAIN_FUNC7 102 -set MAV_TYPE 10 - set MIXER_FILE skip diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1062_tf-r1 b/ROMFS/px4fmu_common/init.d-posix/airframes/1062_tf-r1 index 17efc58534..4e271c77b9 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1062_tf-r1 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1062_tf-r1 @@ -10,6 +10,8 @@ . ${R}etc/init.d/rc.rover_defaults +param set-default MAV_TYPE 10 + param set-default GND_L1_DIST 5 param set-default GND_SP_CTRL_MODE 1 param set-default GND_SPEED_D 3 @@ -33,6 +35,4 @@ param set-default CBRK_AIRSPD_CHK 162128 param set-default GND_MAX_ANG 0.6 param set-default GND_WHEEL_BASE 3.0 -set MAV_TYPE 10 - set MIXER_FILE etc/mixers-sitl/rover_ackermann_sitl.main.mix diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat b/ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat index 08dc4a2bbc..c45d9d78b9 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat @@ -47,6 +47,4 @@ param set-default CA_R_REV 3 param set-default PWM_MAIN_FUNC1 101 param set-default PWM_MAIN_FUNC2 102 -set MAV_TYPE 11 - set MIXER skip diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/3011_hexarotor_x b/ROMFS/px4fmu_common/init.d-posix/airframes/3011_hexarotor_x index a0f3a04294..85f14ef4d6 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/3011_hexarotor_x +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/3011_hexarotor_x @@ -9,6 +9,8 @@ . ${R}etc/init.d/rc.mc_defaults +param set-default MAV_TYPE 13 + param set-default MC_PITCHRATE_P 0.1 param set-default MC_PITCHRATE_I 0.05 param set-default MC_PITCH_P 6.0 @@ -24,6 +26,4 @@ param set-default TRIG_MODE 4 param set-default MNT_MODE_IN 4 param set-default MNT_DO_STAB 2 -set MAV_TYPE 13 - set MIXER hexa_x diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/6011_typhoon_h480 b/ROMFS/px4fmu_common/init.d-posix/airframes/6011_typhoon_h480 index 967e0535e3..2cdd4a5314 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/6011_typhoon_h480 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/6011_typhoon_h480 @@ -7,6 +7,8 @@ . ${R}etc/init.d/rc.mc_defaults +param set-default MAV_TYPE 13 + param set-default MC_PITCHRATE_P 0.0800 param set-default MC_PITCHRATE_I 0.0400 param set-default MC_PITCHRATE_D 0.0010 @@ -26,6 +28,4 @@ param set-default MNT_MODE_IN 4 param set-default MNT_MODE_OUT 2 param set-default MAV_PROTO_VER 2 -set MAV_TYPE 13 - set MIXER hexa_x diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc b/ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc index 39e52f2243..39e360f8be 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc @@ -7,6 +7,8 @@ . ${R}etc/init.d/rc.mc_defaults +param set-default MAV_TYPE 13 + param set-default SYS_CTRL_ALLOC 1 param set-default MC_PITCHRATE_P 0.0800 @@ -58,7 +60,5 @@ param set-default PWM_MAIN_FUNC4 104 param set-default PWM_MAIN_FUNC5 105 param set-default PWM_MAIN_FUNC6 106 -set MAV_TYPE 13 - set MIXER skip set MIXER_AUX none diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index 13ff820f4d..462aba0dcc 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -24,7 +24,6 @@ fi # initialize script variables set IO_PRESENT no -set MAV_TYPE none set MIXER none set MIXER_AUX none set MIXER_FILE none diff --git a/ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d index dfaaa816d0..1b3293dfd9 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d +++ b/ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d @@ -36,4 +36,5 @@ param set-default MC_PITCHRATE_P 0.19 param set-default MC_PITCHRATE_I 0.05 param set-default MC_PITCHRATE_D 0.004 param set-default MC_YAW_P 4 + set MIXER quad_w diff --git a/ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil b/ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil index bc399db45a..5cea20a505 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil @@ -104,7 +104,7 @@ param set-default CBRK_SUPPLY_CHK 894281 param set-default COM_PREARM_MODE 0 param set-default CBRK_IO_SAFETY 22027 -set MAV_TYPE 22 +param set-default MAV_TYPE 22 set MIXER standard_vtol_hitl diff --git a/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil b/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil index 1e0c9d5f36..a9046c6aff 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil @@ -47,7 +47,7 @@ param set-default HIL_ACT_FUNC6 201 param set-default HIL_ACT_REV 32 param set-default MAV_TYPE 19 -set MAV_TYPE 19 + set MIXER vtol_tailsitter_duo_sat set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard b/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard index b95fc758a3..4bdbb30015 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard +++ b/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard @@ -54,7 +54,8 @@ param set-default PWM_AUX_DIS5 950 param set-default VT_TYPE 2 param set-default VT_MOT_ID 1234 param set-default VT_FW_MOT_OFFID 1234 -set MAV_TYPE 22 + +param set-default MAV_TYPE 22 set MIXER quad_x set MIXER_AUX vtol_AAERT diff --git a/ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol b/ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol index 1badc86deb..85e55bbe9d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol +++ b/ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol @@ -19,7 +19,6 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default MAV_TYPE 19 param set-default MC_ROLL_P 6 @@ -38,7 +37,6 @@ param set-default VT_IDLE_PWM_MC 1080 param set-default VT_ELEV_MC_LOCK 0 param set-default VT_MOT_ID 12 param set-default VT_TYPE 0 -set MAV_TYPE 19 set MIXER vtol_tailsitter_duo diff --git a/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 b/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 index 27f85e0291..583a045696 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 +++ b/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 @@ -23,6 +23,7 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-default MAV_TYPE 21 param set-default MC_ROLL_P 7 param set-default MC_ROLLRATE_P 0.19 @@ -45,7 +46,6 @@ param set-default VT_TILT_TRANS 0.5 param set-default VT_TILT_FW 0.9 param set-default VT_ELEV_MC_LOCK 0 param set-default VT_TYPE 1 -set MAV_TYPE 21 set MIXER firefly6 set MIXER_AUX firefly6 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter b/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter index bb87b6c30e..e88f711105 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter @@ -13,6 +13,8 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-default MAV_TYPE 20 + param set-default CA_AIRFRAME 4 param set-default CA_ROTOR_COUNT 4 param set-default CA_ROTOR0_PX 0.15 @@ -38,7 +40,6 @@ param set-default PWM_MAIN_MAX 2000 param set-default VT_MOT_ID 1234 param set-default VT_IDLE_PWM_MC 1080 param set-default VT_TYPE 0 -set MAV_TYPE 20 set MIXER quad_x_vtol diff --git a/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter b/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter index c4fc1ad0a6..5da3d19aba 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter @@ -22,13 +22,13 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-default MAV_TYPE 20 + param set-default PWM_MAIN_MAX 2000 param set-default VT_IDLE_PWM_MC 1080 param set-default VT_TYPE 0 -set MAV_TYPE 20 - set MIXER quad_+_vtol set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad b/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad index 0fcb124a3b..8949f18f20 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad +++ b/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad @@ -52,7 +52,6 @@ param set-default VT_MOT_ID 1234 param set-default VT_FW_MOT_OFFID 1234 param set-default VT_IDLE_PWM_MC 1080 param set-default VT_TYPE 2 -set MAV_TYPE 22 set MIXER quad_x set MIXER_AUX vtol_AAERT diff --git a/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta b/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta index be64f070c0..2207475135 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta +++ b/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta @@ -41,7 +41,6 @@ param set-default VT_FW_MOT_OFFID 1234 param set-default VT_F_TRANS_THR 0.75 param set-default VT_IDLE_PWM_MC 1080 param set-default VT_TYPE 2 -set MAV_TYPE 22 set MIXER quad_x set MIXER_AUX vtol_delta diff --git a/ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad b/ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad index b32840098b..7671ec1cf5 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad +++ b/ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad @@ -33,7 +33,6 @@ param set-default VT_MOT_ID 1234 param set-default VT_FW_MOT_OFFID 1234 param set-default VT_IDLE_PWM_MC 1080 param set-default VT_TYPE 2 -set MAV_TYPE 22 set MIXER quad_x set MIXER_AUX vtol_AAVVT diff --git a/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger b/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger index 41077bccf7..94e2a1a913 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger +++ b/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger @@ -46,7 +46,6 @@ param set-default VT_IDLE_PWM_MC 1080 param set-default VT_MOT_ID 1234 param set-default VT_FW_MOT_OFFID 1234 param set-default VT_TYPE 2 -set MAV_TYPE 22 set MIXER quad_x set MIXER_AUX vtol_AAERT diff --git a/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger b/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger index 2176a18b4b..312ffd3e5b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger +++ b/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger @@ -77,8 +77,6 @@ param set-default VT_TRANS_MIN_TM 5 param set-default VT_TRANS_TIMEOUT 30 param set-default VT_TYPE 2 -set MAV_TYPE 22 - set MIXER quad_x set MIXER_AUX vtol_AAERT diff --git a/ROMFS/px4fmu_common/init.d/airframes/13010_claire b/ROMFS/px4fmu_common/init.d/airframes/13010_claire index 5d4976d9b3..1fa1248e15 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13010_claire +++ b/ROMFS/px4fmu_common/init.d/airframes/13010_claire @@ -13,6 +13,8 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-defualt MAV_TYPE 21 + param set-default PWM_AUX_DISARM 1000 param set-default PWM_AUX_MAX 2000 param set-default PWM_AUX_MIN 1000 @@ -28,7 +30,6 @@ param set-default VT_TILT_MC 0.08 param set-default VT_TILT_TRANS 0.5 param set-default VT_ELEV_MC_LOCK 0 param set-default VT_TYPE 1 -set MAV_TYPE 21 set MIXER claire set MIXER_AUX claire diff --git a/ROMFS/px4fmu_common/init.d/airframes/13012_convergence b/ROMFS/px4fmu_common/init.d/airframes/13012_convergence index f56f7e2177..f9e0721291 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13012_convergence +++ b/ROMFS/px4fmu_common/init.d/airframes/13012_convergence @@ -22,6 +22,8 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-defualt MAV_TYPE 21 + param set-default CBRK_AIRSPD_CHK 162128 param set-default FW_ARSP_MODE 1 @@ -64,7 +66,6 @@ param set-default VT_TRANS_MIN_TM 1.2 param set-default VT_TRANS_P2_DUR 1.3 param set-default VT_ELEV_MC_LOCK 0 param set-default VT_TYPE 1 -set MAV_TYPE 21 set MIXER vtol_convergence diff --git a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad index 6ae2f229a0..1448257981 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad +++ b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad @@ -22,6 +22,8 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-default MAV_TYPE 22 + param set-default BAT1_CAPACITY 23000 param set-default BAT1_N_CELLS 4 param set-default BAT1_R_INTERNAL 0.0025 @@ -134,7 +136,6 @@ param set-default VT_TRANS_TIMEOUT 22 param set-default VT_F_TRANS_RAMP 4 param set-default COM_RC_OVERRIDE 0 -set MAV_TYPE 22 set MIXER deltaquad set MIXER_AUX pass diff --git a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark index 5ea1e76d9f..5d1be9b55f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark +++ b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark @@ -23,6 +23,8 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-default MAV_TYPE 22 + param set-default BAT1_N_CELLS 6 param set-default FW_AIRSPD_MAX 30 @@ -94,8 +96,6 @@ param set-default VT_PSHER_RMP_DT 2 param set-default VT_TRANS_MIN_TM 4 param set-default VT_TYPE 2 -set MAV_TYPE 22 - set MIXER babyshark set MIXER_AUX pass diff --git a/ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor b/ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor index 1ef3c9a1f0..d62b42ee71 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor +++ b/ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor @@ -27,6 +27,8 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-default MAV_TYPE 21 + param set-default VT_IDLE_PWM_MC 1100 param set-default VT_TYPE 1 param set-default VT_MOT_ID 1234 @@ -57,8 +59,6 @@ param set-default CA_SV_CS3_TRQ_Y 1.0 param set-default CA_SV_CS3_TYPE 4 param set-default CA_SV_TL_COUNT 4 -set MAV_TYPE 21 - set MIXER quad_x set MIXER_AUX vtol_TTTTAAER diff --git a/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo b/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo index 94609118e3..c56a10d692 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo +++ b/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo @@ -31,7 +31,6 @@ param set-default PWM_AUX_DIS5 950 param set-default VT_TYPE 2 param set-default VT_MOT_ID 12345678 param set-default VT_FW_MOT_OFFID 12345678 -set MAV_TYPE 22 set MIXER octo_cox set MIXER_AUX vtol_AAERT diff --git a/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter b/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter index 06f650be35..d235153980 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter @@ -19,6 +19,8 @@ . ${R}etc/init.d/rc.vtol_defaults +param set-default MAV_TYPE 19 + param set-default VT_ELEV_MC_LOCK 0 param set-default VT_MOT_COUNT 2 param set-default VT_TYPE 0 @@ -37,8 +39,6 @@ param set-default CA_SV_CS1_TRQ_P 0.5 param set-default CA_SV_CS1_TRQ_Y -0.5 param set-default CA_SV_CS1_TYPE 6 -param set-default MAV_TYPE 19 -set MAV_TYPE 19 set MIXER vtol_tailsitter_duo set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+ b/ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+ index 5607827708..e12393eb6e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+ +++ b/ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+ @@ -18,4 +18,7 @@ . ${R}etc/init.d/rc.mc_defaults +# MAV_TYPE_TRICOPTER 15 +param set-default MAV_TYPE 15 + set MIXER tri_y_yaw+ diff --git a/ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw- b/ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw- index 8ac71f0471..425728199c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw- +++ b/ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw- @@ -18,4 +18,7 @@ . ${R}etc/init.d/rc.mc_defaults +# MAV_TYPE_TRICOPTER 15 +param set-default MAV_TYPE 15 + set MIXER tri_y_yaw- diff --git a/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli b/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli index da685868e2..a8a65b7333 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli +++ b/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli @@ -17,7 +17,9 @@ # . ${R}etc/init.d/rc.mc_defaults -set MIXER coax + +# MAV_TYPE_COAXIAL 3 +param set-default MAV_TYPE 3 param set-default MC_ROLLRATE_P 0.17 param set-default MC_ROLLRATE_I 0.05 @@ -36,6 +38,9 @@ param set-default PWM_MAIN_RATE 400 param set-default RTL_RETURN_ALT 30 param set-default RTL_DESCEND_ALT 10 + +set MIXER coax + # This is the gimbal pass mixer set MIXER_AUX pass diff --git a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter index b97347ad56..ac1c5475c1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter +++ b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter @@ -20,7 +20,7 @@ . ${R}etc/init.d/rc.mc_defaults # Configure as helicopter (number 4 defined in commander_helper.cpp) -set MAV_TYPE 4 +param set-default MAV_TYPE 4 set MIXER blade130 diff --git a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 index 3482826827..e677228cd8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 +++ b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 @@ -41,5 +41,6 @@ param set-default FW_R_LIM 40 param set-default FW_P_LIM_MAX 25 param set-default FW_P_LIM_MIN -5 param set-default FW_P_RMAX_NEG 20 + set MIXER TF-G2 set MIXER_AUX pass diff --git a/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 b/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 index dfc006ee82..b62f1a9831 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 +++ b/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 @@ -24,8 +24,5 @@ param set-default MAV_0_CONFIG 102 param set-default GPS_UBX_DYNMODEL 8 param set-default SER_TEL2_BAUD 9600 -set MAV_TYPE 8 -param set MAV_TYPE ${MAV_TYPE} - set MIXER IO_pass set MIXER_AUX pass diff --git a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox index dc2a23a5ca..d2a4e75f48 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox +++ b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox @@ -26,7 +26,7 @@ # @board px4_fmu-v2 exclude # -set VEHICLE_TYPE mc +. ${R}etc/init.d/rc.mc_defaults param set-default NAV_ACC_RAD 2 @@ -39,6 +39,7 @@ param set-default PWM_MAIN_RATE 400 param set-default RTL_DESCEND_ALT 10 param set-default RTL_RETURN_ALT 30 + set MIXER dodeca_top_cox set MIXER_AUX dodeca_bottom_cox diff --git a/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing b/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing index 44c5ec9d26..d9a18853a2 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing @@ -41,9 +41,6 @@ param set-default FW_RR_P 0.04 param set-default PWM_MAIN_DISARM 1000 -# Configure this as plane. -set MAV_TYPE 1 - # Set mixer. set MIXER fw_generic_wing diff --git a/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq b/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq index 118cbeca21..74c99d69d3 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq +++ b/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq @@ -24,8 +24,6 @@ set MIXER quad_s250aq -set MAV_TYPE 2 - param set-default ATT_BIAS_MAX 0 param set-default CBRK_IO_SAFETY 22027 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo index a3ec1dc227..c2147e2d1f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo @@ -21,10 +21,7 @@ # @board cuav_x7pro exclude # -set VEHICLE_TYPE mc -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_defaults # Attitude & rate gains param set-default MC_ROLLRATE_D 0.0013 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s index d04238b0fd..bcafa15972 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s +++ b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s @@ -21,10 +21,7 @@ # @maintainer Hyon Lim # -set VEHICLE_TYPE mc -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_defaults # Attitude & rate gains param set-default MC_ROLLRATE_D 0.0013 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor b/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor index 54fd22a5dc..d9d8a8bb63 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor +++ b/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor @@ -24,10 +24,6 @@ . ${R}etc/init.d/rc.mc_defaults - -# Configure this as Quadrotor -# set MAV_TYPE 14 - # Set mixer set MIXER tilt_quad set MIXER_AUX tilt_quad diff --git a/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle b/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle index e00793cd4a..2c79163b34 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle +++ b/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle @@ -48,8 +48,6 @@ param set-default NAV_ACC_RAD 0.5 param set-default PWM_MAIN_DISARM 1500 param set-default PWM_MAIN_MAX 2000 param set-default PWM_MAIN_MIN 1000 -# Configure this as rover -set MAV_TYPE 10 # Set mixer set MIXER rover_generic diff --git a/ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover b/ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover index 7a18aa5b11..118e6915c9 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover +++ b/ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover @@ -76,9 +76,6 @@ param set-default RBCLW_SER_CFG 104 # Start this driver after setting parameters, because the driver uses some of those parameters. # roboclaw start /dev/ttyS3 -# Configure this as rover -set MAV_TYPE 10 - # Set mixer set MIXER generic_diff_rover diff --git a/ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx b/ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx index cb1dd1eaea..1c1d55b392 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx +++ b/ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx @@ -65,9 +65,6 @@ param set-default PWM_MAIN_MIN4 970 # Enable Airspeed check circuit breaker because Rovers will have no airspeed sensor param set-default CBRK_AIRSPD_CHK 162128 -# Configure this as rover -set MAV_TYPE 10 - # Set mixer set MIXER rover_diff_and_servo diff --git a/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic b/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic index 3c350469bc..e0b33a9534 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic +++ b/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic @@ -16,7 +16,4 @@ # disable circuit breaker for airspeed sensor param set-default CBRK_AIRSPD_CHK 162128 -set MAV_TYPE 12 -param set MAV_TYPE ${MAV_TYPE} - set MIXER uuv_x diff --git a/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus b/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus index d4fd066e67..8ea8646956 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus +++ b/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus @@ -16,7 +16,4 @@ # disable circuit breaker for airspeed sensor param set-default CBRK_AIRSPD_CHK 162128 -set MAV_TYPE 12 -param set MAV_TYPE ${MAV_TYPE} - set MIXER uuv_x diff --git a/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x b/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x index bccd44fc9a..c2bbb26cdb 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x +++ b/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x @@ -23,6 +23,9 @@ . ${R}etc/init.d/rc.mc_defaults +# MAV_TYPE_HEXAROTOR 13 +param set-default MAV_TYPE 13 + param set-default CA_ROTOR_COUNT 6 param set-default CA_ROTOR0_PX 0.0 param set-default CA_ROTOR0_PY 0.5 diff --git a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r index bc8f575fd1..70a88e3fdf 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r +++ b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r @@ -27,9 +27,8 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER hexa_x -set PWM_OUT 12345678 - +# MAV_TYPE_HEXAROTOR 13 +param set-default MAV_TYPE 13 ############################################### # Attitude & rate gains @@ -120,3 +119,7 @@ param set-default MAV_1_MODE 2 param set-default MAV_1_FORWARD 1 param set-default MAV_1_RATE 800000 param set-default SER_TEL2_BAUD 921600 + + +set MIXER hexa_x +set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ b/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ index b95143a44b..e1db21eca3 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ +++ b/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ @@ -23,6 +23,9 @@ . ${R}etc/init.d/rc.mc_defaults +# MAV_TYPE_HEXAROTOR 13 +param set-default MAV_TYPE 13 + param set-default CA_ROTOR_COUNT 6 param set-default CA_ROTOR0_PX 0.5 param set-default CA_ROTOR0_PY 0.0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x b/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x index 02895522f7..cabae69975 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x +++ b/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x @@ -25,6 +25,9 @@ . ${R}etc/init.d/rc.mc_defaults +# MAV_TYPE_OCTOROTOR 14 +param set-default MAV_TYPE 14 + param set-default CA_ROTOR_COUNT 8 param set-default CA_ROTOR0_KM -0.05 param set-default CA_ROTOR0_PX 0.46 diff --git a/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ b/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ index b61a1f95b0..95c2479560 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ +++ b/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ @@ -25,6 +25,9 @@ . ${R}etc/init.d/rc.mc_defaults +# MAV_TYPE_OCTOROTOR 14 +param set-default MAV_TYPE 14 + set MIXER octo_+ set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/rc.airship_defaults b/ROMFS/px4fmu_common/init.d/rc.airship_defaults index 25ac61e212..8c51643915 100644 --- a/ROMFS/px4fmu_common/init.d/rc.airship_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.airship_defaults @@ -7,6 +7,9 @@ set VEHICLE_TYPE airship +# MAV_TYPE_AIRSHIP 7 +param set-default MAV_TYPE 7 + # # This is the gimbal pass mixer. # diff --git a/ROMFS/px4fmu_common/init.d/rc.balloon_defaults b/ROMFS/px4fmu_common/init.d/rc.balloon_defaults index 302d81ae90..6f7d925e0c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.balloon_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.balloon_defaults @@ -7,6 +7,9 @@ set VEHICLE_TYPE fw +# MAV_TYPE_FREE_BALLOON 8 +param set-default MAV_TYPE 8 + # # Default parameters for balloon UAVs. # diff --git a/ROMFS/px4fmu_common/init.d/rc.boat_defaults b/ROMFS/px4fmu_common/init.d/rc.boat_defaults index 63325c2f8b..a281b8395e 100644 --- a/ROMFS/px4fmu_common/init.d/rc.boat_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.boat_defaults @@ -7,6 +7,9 @@ set VEHICLE_TYPE rover +# MAV_TYPE_SURFACE_BOAT 11 +param set-default MAV_TYPE 11 + # # Default parameters for UGVs. # diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 94828ac47c..2fcd351db2 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -7,6 +7,9 @@ set VEHICLE_TYPE fw +# MAV_TYPE_FIXED_WING 1 +param set-default MAV_TYPE 1 + # # Default parameters for fixed wing UAVs. # diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index c04ffa426c..d057bf3050 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -7,6 +7,9 @@ set VEHICLE_TYPE mc +# MAV_TYPE_QUADROTOR 2 +param set-default MAV_TYPE 2 + if param compare IMU_GYRO_RATEMAX 400 then param set-default IMU_GYRO_RATEMAX 800 diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_defaults b/ROMFS/px4fmu_common/init.d/rc.rover_defaults index e1282549b0..d7e826c49c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.rover_defaults @@ -7,6 +7,9 @@ set VEHICLE_TYPE rover +# MAV_TYPE_GROUND_ROVER 10 +param set-default MAV_TYPE 10 + # # Default parameters for UGVs. # diff --git a/ROMFS/px4fmu_common/init.d/rc.uuv_defaults b/ROMFS/px4fmu_common/init.d/rc.uuv_defaults index 6d525fd0e1..01e755fc29 100644 --- a/ROMFS/px4fmu_common/init.d/rc.uuv_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.uuv_defaults @@ -7,6 +7,9 @@ set VEHICLE_TYPE uuv +# MAV_TYPE_SUBMARINE 12 +param set-default MAV_TYPE 12 + param set-default PWM_MAIN_MAX 1950 param set-default PWM_MAIN_MIN 1050 param set-default PWM_MAIN_DISARM 1500 diff --git a/ROMFS/px4fmu_common/init.d/rc.vehicle_setup b/ROMFS/px4fmu_common/init.d/rc.vehicle_setup index e9f01eae5d..aac1b76fed 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vehicle_setup +++ b/ROMFS/px4fmu_common/init.d/rc.vehicle_setup @@ -12,19 +12,9 @@ if [ $VEHICLE_TYPE = fw ] then if [ $MIXER = none ] then - # Set default mixer for fixed wing if not defined. - set MIXER AERT + echo "FW mixer undefined" fi - if [ $MAV_TYPE = none ] - then - # Set a default MAV_TYPE = 1 if not defined. - set MAV_TYPE 1 - fi - - # Set the mav type parameter. - param set MAV_TYPE ${MAV_TYPE} - # Load mixer and configure outputs. . ${R}etc/init.d/rc.interface @@ -42,41 +32,6 @@ then echo "MC mixer undefined" fi - if [ $MAV_TYPE = none ] - then - # Set a default MAV_TYPE = 2 if not defined. - set MAV_TYPE 2 - - # Use mixer to detect vehicle type - if [ $MIXER = coax ] - then - set MAV_TYPE 3 - fi - if [ $MIXER = hexa_x -o $MIXER = hexa_+ ] - then - set MAV_TYPE 13 - fi - if [ $MIXER = hexa_cox ] - then - set MAV_TYPE 13 - fi - if [ $MIXER = octo_x -o $MIXER = octo_+ ] - then - set MAV_TYPE 14 - fi - if [ $MIXER = octo_cox -o $MIXER = octo_cox_w ] - then - set MAV_TYPE 14 - fi - if [ $MIXER = tri_y_yaw- -o $MIXER = tri_y_yaw+ ] - then - set MAV_TYPE 15 - fi - fi - - # Set the mav type parameter. - param set MAV_TYPE ${MAV_TYPE} - # Load mixer and configure outputs. . ${R}etc/init.d/rc.interface @@ -91,19 +46,9 @@ if [ $VEHICLE_TYPE = rover ] then if [ $MIXER = none ] then - # Set default mixer for UGV if not defined. - set MIXER rover_generic - fi - - if [ $MAV_TYPE = none ] - then - # Set a default MAV_TYPE = 10 if not defined. - set MAV_TYPE 10 + echo "rover mixer undefined" fi - # Set the mav type parameter. - param set MAV_TYPE ${MAV_TYPE} - # Load mixer and configure outputs. . ${R}etc/init.d/rc.interface @@ -121,25 +66,6 @@ then echo "VTOL mixer undefined" fi - if [ $MAV_TYPE = none ] - then - # Set a default MAV_TYPE = 19 if not defined. - set MAV_TYPE 19 - - # Use mixer to detect vehicle type. - if [ $MIXER = firefly6 ] - then - set MAV_TYPE 21 - fi - if [ $MIXER = quad_x_pusher_vtol ] - then - set MAV_TYPE 22 - fi - fi - - # Set the mav type parameter. - param set MAV_TYPE ${MAV_TYPE} - # Load mixer and configure outputs. . ${R}etc/init.d/rc.interface @@ -157,15 +83,6 @@ then echo "Airship mixer undefined" fi - if [ $MAV_TYPE = none ] - then - # Set a default MAV_TYPE = 7 if not defined. - set MAV_TYPE 7 - fi - - # Set the mav type parameter. - param set MAV_TYPE ${MAV_TYPE} - # Load mixer and configure outputs. . ${R}etc/init.d/rc.interface @@ -183,19 +100,11 @@ then echo "UUV mixer undefined" fi - if [ $MAV_TYPE = none ] - then - # Set default MAV_TYPE to submarine if not defined - set MAV_TYPE 12 - fi - - param set MAV_TYPE ${MAV_TYPE} # Load mixer and configure outputs. . ${R}etc/init.d/rc.interface # Start standard vtol apps. . ${R}etc/init.d/rc.uuv_apps - fi diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index 06146447ed..425d10c378 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -7,6 +7,9 @@ set VEHICLE_TYPE vtol +# MAV_TYPE_VTOL_RESERVED2 22 +param set-default MAV_TYPE 22 + param set-default MIS_TAKEOFF_ALT 20 param set-default MIS_YAW_TMT 10 diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index df7c436a62..f560f1fea1 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -29,7 +29,6 @@ set IOFW "/etc/extras/px4_io-v2_default.bin" set IO_PRESENT no set LOGGER_ARGS "" set LOGGER_BUF 8 -set MAV_TYPE none set MIXER none set MIXER_AUX none set MIXER_FILE none @@ -573,7 +572,6 @@ unset IO_PRESENT unset IOFW unset LOGGER_ARGS unset LOGGER_BUF -unset MAV_TYPE unset MIXER unset MIXER_AUX unset MIXER_FILE diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index dfff253985..a574b6a716 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -69,16 +69,15 @@ #define VEHICLE_TYPE_COAXIAL 3 #define VEHICLE_TYPE_HELICOPTER 4 #define VEHICLE_TYPE_GROUND_ROVER 10 +#define VEHICLE_TYPE_BOAT 11 +#define VEHICLE_TYPE_SUBMARINE 12 #define VEHICLE_TYPE_HEXAROTOR 13 #define VEHICLE_TYPE_OCTOROTOR 14 #define VEHICLE_TYPE_TRICOPTER 15 #define VEHICLE_TYPE_VTOL_DUOROTOR 19 #define VEHICLE_TYPE_VTOL_QUADROTOR 20 #define VEHICLE_TYPE_VTOL_TILTROTOR 21 -#define VEHICLE_TYPE_VTOL_RESERVED2 22 -#define VEHICLE_TYPE_VTOL_RESERVED3 23 -#define VEHICLE_TYPE_VTOL_RESERVED4 24 -#define VEHICLE_TYPE_VTOL_RESERVED5 25 +#define VEHICLE_TYPE_VTOL_RESERVED2 22 // VTOL standard #define BLINK_MSG_TIME 700000 // 3 fast blinks (in us) @@ -101,10 +100,7 @@ bool is_vtol(const vehicle_status_s ¤t_status) return (current_status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR || current_status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR || current_status.system_type == VEHICLE_TYPE_VTOL_TILTROTOR || - current_status.system_type == VEHICLE_TYPE_VTOL_RESERVED2 || - current_status.system_type == VEHICLE_TYPE_VTOL_RESERVED3 || - current_status.system_type == VEHICLE_TYPE_VTOL_RESERVED4 || - current_status.system_type == VEHICLE_TYPE_VTOL_RESERVED5); + current_status.system_type == VEHICLE_TYPE_VTOL_RESERVED2); } bool is_vtol_tailsitter(const vehicle_status_s ¤t_status) diff --git a/src/modules/mavlink/mavlink_params.c b/src/modules/mavlink/mavlink_params.c index cd58e78ec9..aa9a5e8404 100644 --- a/src/modules/mavlink/mavlink_params.c +++ b/src/modules/mavlink/mavlink_params.c @@ -75,39 +75,28 @@ PARAM_DEFINE_INT32(MAV_SIK_RADIO_ID, 0); /** * MAVLink airframe type * - * @min 1 - * @max 27 + * @min 0 + * @max 22 * @value 0 Generic micro air vehicle * @value 1 Fixed wing aircraft * @value 2 Quadrotor * @value 3 Coaxial helicopter * @value 4 Normal helicopter with tail rotor - * @value 5 Ground installation - * @value 6 Operator control unit / ground control station * @value 7 Airship, controlled * @value 8 Free balloon, uncontrolled - * @value 9 Rocket * @value 10 Ground rover * @value 11 Surface vessel, boat, ship * @value 12 Submarine * @value 13 Hexarotor * @value 14 Octorotor * @value 15 Tricopter - * @value 16 Flapping wing - * @value 17 Kite - * @value 18 Onboard companion controller - * @value 19 Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. - * @value 20 Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. - * @value 21 Tiltrotor VTOL - * @value 22 VTOL reserved 2 - * @value 23 VTOL reserved 3 - * @value 24 VTOL reserved 4 - * @value 25 VTOL reserved 5 - * @value 26 Onboard gimbal - * @value 27 Onboard ADSB peripheral + * @value 19 VTOL Tailsitter Duo + * @value 20 VTOL Tailsitter Quad + * @value 21 VTOL Tiltrotor + * @value 22 VTOL Standard (quadplane) * @group MAVLink */ -PARAM_DEFINE_INT32(MAV_TYPE, 2); +PARAM_DEFINE_INT32(MAV_TYPE, 0); /** * Use/Accept HIL GPS message even if not in HIL mode