Browse Source

ROMFS: MAV_TYPE cleanup

- set MAV_TYPE as a parameter default per vehicle type, or airframe if necessary
 - cleanup MAV_TYPE param metadata and commander helper to only include
what's currently used in PX4
v1.13.0-BW
Daniel Agar 3 years ago
parent
commit
36e6527013
  1. 3
      ROMFS/px4fmu_common/init.d-posix/airframes/1020_uuv_generic
  2. 3
      ROMFS/px4fmu_common/init.d-posix/airframes/1021_uuv_hippocampus
  3. 1
      ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy
  4. 2
      ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol
  5. 4
      ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter
  6. 4
      ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor
  7. 2
      ROMFS/px4fmu_common/init.d-posix/airframes/1043_standard_vtol_drop
  8. 2
      ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover
  9. 2
      ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover
  10. 4
      ROMFS/px4fmu_common/init.d-posix/airframes/1062_tf-r1
  11. 2
      ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat
  12. 4
      ROMFS/px4fmu_common/init.d-posix/airframes/3011_hexarotor_x
  13. 4
      ROMFS/px4fmu_common/init.d-posix/airframes/6011_typhoon_h480
  14. 4
      ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc
  15. 1
      ROMFS/px4fmu_common/init.d-posix/rcS
  16. 1
      ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d
  17. 2
      ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil
  18. 2
      ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil
  19. 3
      ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard
  20. 2
      ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol
  21. 2
      ROMFS/px4fmu_common/init.d/airframes/13002_firefly6
  22. 3
      ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter
  23. 4
      ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter
  24. 1
      ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad
  25. 1
      ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta
  26. 1
      ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad
  27. 1
      ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger
  28. 2
      ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger
  29. 3
      ROMFS/px4fmu_common/init.d/airframes/13010_claire
  30. 3
      ROMFS/px4fmu_common/init.d/airframes/13012_convergence
  31. 3
      ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad
  32. 4
      ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark
  33. 4
      ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor
  34. 1
      ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo
  35. 4
      ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter
  36. 3
      ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+
  37. 3
      ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw-
  38. 7
      ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli
  39. 2
      ROMFS/px4fmu_common/init.d/airframes/16001_helicopter
  40. 1
      ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2
  41. 3
      ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1
  42. 3
      ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox
  43. 3
      ROMFS/px4fmu_common/init.d/airframes/3033_wingwing
  44. 2
      ROMFS/px4fmu_common/init.d/airframes/4051_s250aq
  45. 5
      ROMFS/px4fmu_common/init.d/airframes/4071_ifo
  46. 5
      ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s
  47. 4
      ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor
  48. 2
      ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle
  49. 3
      ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover
  50. 3
      ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx
  51. 3
      ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic
  52. 3
      ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus
  53. 3
      ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x
  54. 9
      ROMFS/px4fmu_common/init.d/airframes/6002_draco_r
  55. 3
      ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+
  56. 3
      ROMFS/px4fmu_common/init.d/airframes/8001_octo_x
  57. 3
      ROMFS/px4fmu_common/init.d/airframes/9001_octo_+
  58. 3
      ROMFS/px4fmu_common/init.d/rc.airship_defaults
  59. 3
      ROMFS/px4fmu_common/init.d/rc.balloon_defaults
  60. 3
      ROMFS/px4fmu_common/init.d/rc.boat_defaults
  61. 3
      ROMFS/px4fmu_common/init.d/rc.fw_defaults
  62. 3
      ROMFS/px4fmu_common/init.d/rc.mc_defaults
  63. 3
      ROMFS/px4fmu_common/init.d/rc.rover_defaults
  64. 3
      ROMFS/px4fmu_common/init.d/rc.uuv_defaults
  65. 95
      ROMFS/px4fmu_common/init.d/rc.vehicle_setup
  66. 3
      ROMFS/px4fmu_common/init.d/rc.vtol_defaults
  67. 2
      ROMFS/px4fmu_common/init.d/rcS
  68. 12
      src/modules/commander/commander_helper.cpp
  69. 25
      src/modules/mavlink/mavlink_params.c

3
ROMFS/px4fmu_common/init.d-posix/airframes/1020_uuv_generic

@ -8,8 +8,5 @@ @@ -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

3
ROMFS/px4fmu_common/init.d-posix/airframes/1021_uuv_hippocampus

@ -8,8 +8,5 @@ @@ -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

1
ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy

@ -67,4 +67,3 @@ param set-default PWM_MAIN_FUNC7 107 @@ -67,4 +67,3 @@ param set-default PWM_MAIN_FUNC7 107
param set-default PWM_MAIN_FUNC8 108
set MIXER skip

2
ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol

@ -80,7 +80,5 @@ param set-default VT_FW_MOT_OFFID 1234 @@ -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

4
ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter

@ -7,6 +7,8 @@ @@ -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 @@ -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

4
ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor

@ -7,6 +7,8 @@ @@ -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 @@ -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

2
ROMFS/px4fmu_common/init.d-posix/airframes/1043_standard_vtol_drop

@ -51,7 +51,5 @@ param set-default RC_MAP_AUX1 8 @@ -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

2
ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover

@ -37,6 +37,4 @@ param set-default PWM_MAIN_FUNC2 201 @@ -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

2
ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover

@ -37,6 +37,4 @@ param set-default PWM_MAIN_FUNC2 101 @@ -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

4
ROMFS/px4fmu_common/init.d-posix/airframes/1062_tf-r1

@ -10,6 +10,8 @@ @@ -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 @@ -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

2
ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat

@ -47,6 +47,4 @@ param set-default CA_R_REV 3 @@ -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

4
ROMFS/px4fmu_common/init.d-posix/airframes/3011_hexarotor_x

@ -9,6 +9,8 @@ @@ -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 @@ -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

4
ROMFS/px4fmu_common/init.d-posix/airframes/6011_typhoon_h480

@ -7,6 +7,8 @@ @@ -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 @@ -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

4
ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc

@ -7,6 +7,8 @@ @@ -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 @@ -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

1
ROMFS/px4fmu_common/init.d-posix/rcS

@ -24,7 +24,6 @@ fi @@ -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

1
ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d

@ -36,4 +36,5 @@ param set-default MC_PITCHRATE_P 0.19 @@ -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

2
ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil

@ -104,7 +104,7 @@ param set-default CBRK_SUPPLY_CHK 894281 @@ -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

2
ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil

@ -47,7 +47,7 @@ param set-default HIL_ACT_FUNC6 201 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard

@ -54,7 +54,8 @@ param set-default PWM_AUX_DIS5 950 @@ -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

2
ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol

@ -19,7 +19,6 @@ @@ -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 @@ -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

2
ROMFS/px4fmu_common/init.d/airframes/13002_firefly6

@ -23,6 +23,7 @@ @@ -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 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter

@ -13,6 +13,8 @@ @@ -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 @@ -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

4
ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter

@ -22,13 +22,13 @@ @@ -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

1
ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad

@ -52,7 +52,6 @@ param set-default VT_MOT_ID 1234 @@ -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

1
ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta

@ -41,7 +41,6 @@ param set-default VT_FW_MOT_OFFID 1234 @@ -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

1
ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad

@ -33,7 +33,6 @@ param set-default VT_MOT_ID 1234 @@ -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

1
ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger

@ -46,7 +46,6 @@ param set-default VT_IDLE_PWM_MC 1080 @@ -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

2
ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger

@ -77,8 +77,6 @@ param set-default VT_TRANS_MIN_TM 5 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/13010_claire

@ -13,6 +13,8 @@ @@ -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 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/13012_convergence

@ -22,6 +22,8 @@ @@ -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 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad

@ -22,6 +22,8 @@ @@ -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 @@ -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

4
ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark

@ -23,6 +23,8 @@ @@ -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 @@ -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

4
ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor

@ -27,6 +27,8 @@ @@ -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 @@ -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

1
ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo

@ -31,7 +31,6 @@ param set-default PWM_AUX_DIS5 950 @@ -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

4
ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter

@ -19,6 +19,8 @@ @@ -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 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+

@ -18,4 +18,7 @@ @@ -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+

3
ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw-

@ -18,4 +18,7 @@ @@ -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-

7
ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli

@ -17,7 +17,9 @@ @@ -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 @@ -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

2
ROMFS/px4fmu_common/init.d/airframes/16001_helicopter

@ -20,7 +20,7 @@ @@ -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

1
ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2

@ -41,5 +41,6 @@ param set-default FW_R_LIM 40 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1

@ -24,8 +24,5 @@ param set-default MAV_0_CONFIG 102 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox

@ -26,7 +26,7 @@ @@ -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 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/3033_wingwing

@ -41,9 +41,6 @@ param set-default FW_RR_P 0.04 @@ -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

2
ROMFS/px4fmu_common/init.d/airframes/4051_s250aq

@ -24,8 +24,6 @@ @@ -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

5
ROMFS/px4fmu_common/init.d/airframes/4071_ifo

@ -21,10 +21,7 @@ @@ -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

5
ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s

@ -21,10 +21,7 @@ @@ -21,10 +21,7 @@
# @maintainer Hyon Lim <lim@uvify.com>
#
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

4
ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor

@ -24,10 +24,6 @@ @@ -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

2
ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle

@ -48,8 +48,6 @@ param set-default NAV_ACC_RAD 0.5 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover

@ -76,9 +76,6 @@ param set-default RBCLW_SER_CFG 104 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx

@ -65,9 +65,6 @@ param set-default PWM_MAIN_MIN4 970 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic

@ -16,7 +16,4 @@ @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus

@ -16,7 +16,4 @@ @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x

@ -23,6 +23,9 @@ @@ -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

9
ROMFS/px4fmu_common/init.d/airframes/6002_draco_r

@ -27,9 +27,8 @@ @@ -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 @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+

@ -23,6 +23,9 @@ @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/8001_octo_x

@ -25,6 +25,9 @@ @@ -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

3
ROMFS/px4fmu_common/init.d/airframes/9001_octo_+

@ -25,6 +25,9 @@ @@ -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

3
ROMFS/px4fmu_common/init.d/rc.airship_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE airship
# MAV_TYPE_AIRSHIP 7
param set-default MAV_TYPE 7
#
# This is the gimbal pass mixer.
#

3
ROMFS/px4fmu_common/init.d/rc.balloon_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE fw
# MAV_TYPE_FREE_BALLOON 8
param set-default MAV_TYPE 8
#
# Default parameters for balloon UAVs.
#

3
ROMFS/px4fmu_common/init.d/rc.boat_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE rover
# MAV_TYPE_SURFACE_BOAT 11
param set-default MAV_TYPE 11
#
# Default parameters for UGVs.
#

3
ROMFS/px4fmu_common/init.d/rc.fw_defaults

@ -7,6 +7,9 @@ @@ -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.
#

3
ROMFS/px4fmu_common/init.d/rc.mc_defaults

@ -7,6 +7,9 @@ @@ -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

3
ROMFS/px4fmu_common/init.d/rc.rover_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE rover
# MAV_TYPE_GROUND_ROVER 10
param set-default MAV_TYPE 10
#
# Default parameters for UGVs.
#

3
ROMFS/px4fmu_common/init.d/rc.uuv_defaults

@ -7,6 +7,9 @@ @@ -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

95
ROMFS/px4fmu_common/init.d/rc.vehicle_setup

@ -12,19 +12,9 @@ if [ $VEHICLE_TYPE = fw ] @@ -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 @@ -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 ] @@ -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 @@ -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 @@ -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 @@ -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

3
ROMFS/px4fmu_common/init.d/rc.vtol_defaults

@ -7,6 +7,9 @@ @@ -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

2
ROMFS/px4fmu_common/init.d/rcS

@ -29,7 +29,6 @@ set IOFW "/etc/extras/px4_io-v2_default.bin" @@ -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 @@ -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

12
src/modules/commander/commander_helper.cpp

@ -69,16 +69,15 @@ @@ -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 &current_status) @@ -101,10 +100,7 @@ bool is_vtol(const vehicle_status_s &current_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 &current_status)

25
src/modules/mavlink/mavlink_params.c

@ -75,39 +75,28 @@ PARAM_DEFINE_INT32(MAV_SIK_RADIO_ID, 0); @@ -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

Loading…
Cancel
Save