Browse Source

autostart fixes

sbg
Anton Babushkin 11 years ago
parent
commit
524a502a56
  1. 2
      ROMFS/px4fmu_common/init.d/10015_tbs_discovery
  2. 30
      ROMFS/px4fmu_common/init.d/10016_3dr_iris
  3. 30
      ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil
  4. 38
      ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
  5. 30
      ROMFS/px4fmu_common/init.d/4010_dji_f330
  6. 2
      ROMFS/px4fmu_common/init.d/4011_dji_f450
  7. 2
      ROMFS/px4fmu_common/init.d/4012_hk_x550

2
ROMFS/px4fmu_common/init.d/10015_tbs_discovery

@ -12,13 +12,11 @@ then @@ -12,13 +12,11 @@ then
#
param set MC_ATT_P 5.0
param set MC_ATT_I 0.0
param set MC_ATT_D 0.0
param set MC_ATTRATE_P 0.17
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.006
param set MC_YAWPOS_P 0.5
param set MC_YAWPOS_I 0.15
param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0

30
ROMFS/px4fmu_common/init.d/10016_3dr_iris

@ -12,32 +12,28 @@ then @@ -12,32 +12,28 @@ then
#
param set MC_ATT_P 9.0
param set MC_ATT_I 0.0
param set MC_ATT_D 0.0
param set MC_ATTRATE_P 0.13
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.004
param set MC_YAWPOS_P 0.5
param set MC_YAWPOS_I 0.15
param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.8
param set MPC_THR_MIN 0.2
param set MPC_XY_D 0
param set MPC_XY_P 0.5
param set MPC_XY_VEL_D 0
param set MPC_XY_VEL_I 0
param set MPC_XY_VEL_MAX 3
param set MPC_XY_VEL_P 0.2
param set MPC_Z_D 0
param set MPC_Z_P 1
param set MPC_Z_VEL_D 0
param set MPC_Z_VEL_I 0.1
param set MPC_Z_VEL_MAX 2
param set MPC_Z_VEL_P 0.20
param set MPC_TILT_MAX 1.0
param set MPC_THR_MAX 1.0
param set MPC_THR_MIN 0.1
param set MPC_XY_P 1.0
param set MPC_XY_VEL_D 0.01
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_MAX 5
param set MPC_XY_VEL_P 0.1
param set MPC_Z_P 1.0
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_I 0.02
param set MPC_Z_VEL_MAX 3
param set MPC_Z_VEL_P 0.1
param set BAT_V_SCALING 0.00989
param set BAT_C_SCALING 0.0124

30
ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil

@ -15,29 +15,25 @@ then @@ -15,29 +15,25 @@ then
param set MC_ATTRATE_D 0.004
param set MC_ATT_P 7.0
param set MC_ATT_I 0.0
param set MC_ATT_D 0.0
param set MC_YAWPOS_P 2.0
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.3
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.005
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.8
param set MPC_THR_MIN 0.2
param set MPC_XY_D 0
param set MPC_XY_P 0.5
param set MPC_XY_VEL_D 0
param set MPC_XY_VEL_I 0
param set MPC_XY_VEL_MAX 3
param set MPC_XY_VEL_P 0.2
param set MPC_Z_D 0
param set MPC_Z_P 1
param set MPC_Z_VEL_D 0
param set MPC_Z_VEL_I 0.1
param set MPC_Z_VEL_MAX 2
param set MPC_Z_VEL_P 0.20
param set MPC_TILT_MAX 1.0
param set MPC_THR_MAX 1.0
param set MPC_THR_MIN 0.1
param set MPC_XY_P 1.0
param set MPC_XY_VEL_D 0.01
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_MAX 5
param set MPC_XY_VEL_P 0.1
param set MPC_Z_P 1.0
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_I 0.02
param set MPC_Z_VEL_MAX 3
param set MPC_Z_VEL_P 0.1
fi
set HIL yes

38
ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil

@ -5,42 +5,6 @@ @@ -5,42 +5,6 @@
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
#
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
param set MC_ATTRATE_P 0.12
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.004
param set MC_ATT_P 7.0
param set MC_ATT_I 0.0
param set MC_ATT_D 0.0
param set MC_YAWPOS_P 2.0
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.3
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.005
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.8
param set MPC_THR_MIN 0.2
param set MPC_XY_D 0
param set MPC_XY_P 0.5
param set MPC_XY_VEL_D 0
param set MPC_XY_VEL_I 0
param set MPC_XY_VEL_MAX 3
param set MPC_XY_VEL_P 0.2
param set MPC_Z_D 0
param set MPC_Z_P 1
param set MPC_Z_VEL_D 0
param set MPC_Z_VEL_I 0.1
param set MPC_Z_VEL_MAX 2
param set MPC_Z_VEL_P 0.20
fi
sh /etc/ini.d/1001_rc_quad_x.hil
set HIL yes
set VEHICLE_TYPE mc
set MIXER FMU_quad_+

30
ROMFS/px4fmu_common/init.d/4010_dji_f330

@ -12,32 +12,28 @@ then @@ -12,32 +12,28 @@ then
#
param set MC_ATT_P 7.0
param set MC_ATT_I 0.0
param set MC_ATT_D 0.0
param set MC_ATTRATE_P 0.12
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.004
param set MC_YAWPOS_P 2.8
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.05
param set MC_YAWRATE_D 0.0
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.8
param set MPC_THR_MIN 0.2
param set MPC_XY_D 0
param set MPC_XY_P 0.5
param set MPC_XY_VEL_D 0
param set MPC_XY_VEL_I 0
param set MPC_XY_VEL_MAX 3
param set MPC_XY_VEL_P 0.2
param set MPC_Z_D 0
param set MPC_Z_P 1
param set MPC_Z_VEL_D 0
param set MPC_Z_VEL_I 0.1
param set MPC_Z_VEL_MAX 2
param set MPC_Z_VEL_P 0.20
param set MPC_TILT_MAX 1.0
param set MPC_THR_MAX 1.0
param set MPC_THR_MIN 0.1
param set MPC_XY_P 1.0
param set MPC_XY_VEL_D 0.01
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_MAX 5
param set MPC_XY_VEL_P 0.1
param set MPC_Z_P 1.0
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_I 0.02
param set MPC_Z_VEL_MAX 3
param set MPC_Z_VEL_P 0.1
fi
set VEHICLE_TYPE mc

2
ROMFS/px4fmu_common/init.d/4011_dji_f450

@ -12,13 +12,11 @@ then @@ -12,13 +12,11 @@ then
#
param set MC_ATT_P 7.0
param set MC_ATT_I 0.0
param set MC_ATT_D 0.0
param set MC_ATTRATE_P 0.12
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.004
param set MC_YAWPOS_P 2.0
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.3
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.005

2
ROMFS/px4fmu_common/init.d/4012_hk_x550

@ -12,13 +12,11 @@ then @@ -12,13 +12,11 @@ then
#
param set MC_ATT_P 5.5
param set MC_ATT_I 0
param set MC_ATT_D 0
param set MC_ATTRATE_P 0.14
param set MC_ATTRATE_I 0
param set MC_ATTRATE_D 0.006
param set MC_YAWPOS_P 0.6
param set MC_YAWPOS_I 0
param set MC_YAWPOS_D 0
param set MC_YAWRATE_P 0.08
param set MC_YAWRATE_I 0
param set MC_YAWRATE_D 0

Loading…
Cancel
Save