diff options
Diffstat (limited to 'ROMFS/px4fmu_common')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/13000_quadshot | 14 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/Roman_mavlink_stream_conf | 12 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rc.vtol_apps | 15 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rc.vtol_defaults | 63 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/mixers/FMU_quadshot.mix | 15 |
5 files changed, 0 insertions, 119 deletions
diff --git a/ROMFS/px4fmu_common/init.d/13000_quadshot b/ROMFS/px4fmu_common/init.d/13000_quadshot deleted file mode 100644 index 8ee306a38..000000000 --- a/ROMFS/px4fmu_common/init.d/13000_quadshot +++ /dev/null @@ -1,14 +0,0 @@ -#!nsh -# -# Generic quadshot configuration file -# -# Roman Bapst <romanbapst@yahoo.de> -# - -sh /etc/init.d/rc.mc_defaults - -set MIXER FMU_quadshot - -set PWM_OUTPUTS 1234 -set PWM_MIN 1070 -set PWM_MAX 2000
\ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/Roman_mavlink_stream_conf b/ROMFS/px4fmu_common/init.d/Roman_mavlink_stream_conf deleted file mode 100644 index d26e4a372..000000000 --- a/ROMFS/px4fmu_common/init.d/Roman_mavlink_stream_conf +++ /dev/null @@ -1,12 +0,0 @@ -#!nsh -# Configure stream for Mavlink instance on TELEM2 because it is annoying always removing the SDcard -# -#usleep 100000 -#mavlink stream -d /dev/ttyS2 -s ATTITUDE_CONTROLS -r 50 -#usleep 100000 -#mavlink stream -d /dev/ttyS2 -s RC_CHANNELS_RAW -r 50 -#usleep 100000 -#mavlink stream -d /dev/ttyS2 -s VFR_HUD -r 50 -usleep 100000 -mavlink stream -d /dev/ttyS2 -s MANUAL_CONTROL -r 50 -echo "Added additional streams on TELEM2"
\ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_apps b/ROMFS/px4fmu_common/init.d/rc.vtol_apps deleted file mode 100644 index 23ade6d78..000000000 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_apps +++ /dev/null @@ -1,15 +0,0 @@ -#!nsh -# -# Standard apps for vtol: -# att & pos estimator, att & pos control. -# - -attitude_estimator_ekf start -#ekf_att_pos_estimator start -position_estimator_inav start - -vtol_att_control start -mc_att_control start -mc_pos_control start -fw_att_control start -fw_pos_control_l1 start diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults deleted file mode 100644 index f0ea9add0..000000000 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ /dev/null @@ -1,63 +0,0 @@ -#!nsh - -set VEHICLE_TYPE vtol - -if [ $DO_AUTOCONFIG == yes ] -then - #Default parameters for MC - param set MC_ROLL_P 7.0 - param set MC_ROLLRATE_P 0.1 - param set MC_ROLLRATE_I 0.0 - param set MC_ROLLRATE_D 0.003 - param set MC_PITCH_P 7.0 - param set MC_PITCHRATE_P 0.1 - param set MC_PITCHRATE_I 0.0 - param set MC_PITCHRATE_D 0.003 - param set MC_YAW_P 2.8 - param set MC_YAWRATE_P 0.2 - param set MC_YAWRATE_I 0.1 - param set MC_YAWRATE_D 0.0 - param set MC_YAW_FF 0.5 - - 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_P 0.1 - param set MPC_XY_VEL_I 0.02 - param set MPC_XY_VEL_D 0.01 - param set MPC_XY_VEL_MAX 5 - param set MPC_XY_FF 0.5 - param set MPC_Z_P 1.0 - param set MPC_Z_VEL_P 0.1 - param set MPC_Z_VEL_I 0.02 - param set MPC_Z_VEL_D 0.0 - param set MPC_Z_VEL_MAX 3 - param set MPC_Z_FF 0.5 - param set MPC_TILTMAX_AIR 45.0 - param set MPC_TILTMAX_LND 15.0 - param set MPC_LAND_SPEED 1.0 - - param set PE_VELNE_NOISE 0.5 - param set PE_VELD_NOISE 0.7 - param set PE_POSNE_NOISE 0.5 - param set PE_POSD_NOISE 1.0 - - param set NAV_ACCEPT_RAD 2.0 - - # - # Default parameters for FW - # - param set NAV_LAND_ALT 90 - param set NAV_RTL_ALT 100 - param set NAV_RTL_LAND_T -1 - param set NAV_ACCEPT_RAD 50 - param set FW_T_HRATE_P 0.01 - param set FW_T_RLL2THR 15 - param set FW_T_SRATE_P 0.01 - param set FW_T_TIME_CONST 5 -fi - -set PWM_RATE 400 -set PWM_DISARMED 900 -set PWM_MIN 1075 -set PWM_MAX 2000 diff --git a/ROMFS/px4fmu_common/mixers/FMU_quadshot.mix b/ROMFS/px4fmu_common/mixers/FMU_quadshot.mix deleted file mode 100644 index b077ff30a..000000000 --- a/ROMFS/px4fmu_common/mixers/FMU_quadshot.mix +++ /dev/null @@ -1,15 +0,0 @@ -#!nsh -#Quadshot mixer for PX4FMU -#=========================== -R: 4v 10000 10000 10000 0 - -#mixer for the elevons -M: 2 -O: 10000 10000 0 -10000 10000 -S: 1 0 7500 7500 0 -10000 10000 -S: 1 1 8000 8000 0 -10000 10000 - -M: 2 -O: 10000 10000 0 -10000 10000 -S: 1 0 7500 7500 0 -10000 10000 -S: 1 1 -8000 -8000 0 -10000 10000 |