forked from Archive/PX4-Autopilot
Merge branch 'beta' of https://github.com/PX4/Firmware into beta
This commit is contained in:
commit
268f3d757f
|
@ -5,36 +5,10 @@
|
||||||
# Lorenz Meier <lm@inf.ethz.ch>
|
# Lorenz Meier <lm@inf.ethz.ch>
|
||||||
#
|
#
|
||||||
|
|
||||||
echo "HIL Rascal 110 starting.."
|
sh /etc/init.d/rc.fw_defaults
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
echo "HIL Rascal 110 starting.."
|
||||||
then
|
|
||||||
# Set all params here, then disable autoconfig
|
|
||||||
|
|
||||||
param set FW_P_D 0
|
|
||||||
param set FW_P_I 0
|
|
||||||
param set FW_P_IMAX 15
|
|
||||||
param set FW_P_LIM_MAX 50
|
|
||||||
param set FW_P_LIM_MIN -50
|
|
||||||
param set FW_P_P 60
|
|
||||||
param set FW_P_RMAX_NEG 0
|
|
||||||
param set FW_P_RMAX_POS 0
|
|
||||||
param set FW_P_ROLLFF 1.1
|
|
||||||
param set FW_R_D 0
|
|
||||||
param set FW_R_I 5
|
|
||||||
param set FW_R_IMAX 20
|
|
||||||
param set FW_R_P 100
|
|
||||||
param set FW_R_RMAX 100
|
|
||||||
param set FW_THR_CRUISE 0.65
|
|
||||||
param set FW_T_SINK_MAX 5.0
|
|
||||||
param set FW_T_SINK_MIN 4.0
|
|
||||||
param set FW_Y_ROLLFF 1.1
|
|
||||||
param set FW_L1_PERIOD 16
|
|
||||||
param set RC_SCALE_ROLL 1.0
|
|
||||||
param set RC_SCALE_PITCH 1.0
|
|
||||||
fi
|
|
||||||
|
|
||||||
set HIL yes
|
set HIL yes
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
set MIXER FMU_AERT
|
set MIXER FMU_AERT
|
||||||
|
|
|
@ -5,45 +5,8 @@
|
||||||
# Simon Wilks <sjwilks@gmail.com>
|
# Simon Wilks <sjwilks@gmail.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/rc.mc_defaults
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set MC_ROLL_P 5.0
|
|
||||||
param set MC_ROLLRATE_P 0.17
|
|
||||||
param set MC_ROLLRATE_I 0.0
|
|
||||||
param set MC_ROLLRATE_D 0.006
|
|
||||||
param set MC_PITCH_P 5.0
|
|
||||||
param set MC_PITCHRATE_P 0.17
|
|
||||||
param set MC_PITCHRATE_I 0.0
|
|
||||||
param set MC_PITCHRATE_D 0.006
|
|
||||||
param set MC_YAW_P 0.5
|
|
||||||
param set MC_YAWRATE_P 0.2
|
|
||||||
param set MC_YAWRATE_I 0.0
|
|
||||||
param set MC_YAWRATE_D 0.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_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_TILT_MAX 1.0
|
|
||||||
param set MPC_LAND_SPEED 1.0
|
|
||||||
param set MPC_LAND_TILT 0.3
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
|
||||||
set MIXER FMU_quad_w
|
set MIXER FMU_quad_w
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
set PWM_OUTPUTS 1234
|
||||||
set PWM_RATE 400
|
|
|
@ -5,51 +5,17 @@
|
||||||
# Anton Babushkin <anton.babushkin@me.com>
|
# Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
|
sh /etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
then
|
then
|
||||||
#
|
#
|
||||||
# Default parameters for this platform
|
# Default parameters for this platform
|
||||||
#
|
#
|
||||||
param set MC_ROLL_P 9.0
|
|
||||||
param set MC_ROLLRATE_P 0.13
|
|
||||||
param set MC_ROLLRATE_I 0.0
|
|
||||||
param set MC_ROLLRATE_D 0.004
|
|
||||||
param set MC_PITCH_P 9.0
|
|
||||||
param set MC_PITCHRATE_P 0.13
|
|
||||||
param set MC_PITCHRATE_I 0.0
|
|
||||||
param set MC_PITCHRATE_D 0.004
|
|
||||||
param set MC_YAW_P 0.5
|
|
||||||
param set MC_YAWRATE_P 0.2
|
|
||||||
param set MC_YAWRATE_I 0.0
|
|
||||||
param set MC_YAWRATE_D 0.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_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_TILT_MAX 1.0
|
|
||||||
param set MPC_LAND_SPEED 1.0
|
|
||||||
param set MPC_LAND_TILT 0.3
|
|
||||||
|
|
||||||
param set BAT_V_SCALING 0.00989
|
param set BAT_V_SCALING 0.00989
|
||||||
param set BAT_C_SCALING 0.0124
|
param set BAT_C_SCALING 0.0124
|
||||||
fi
|
fi
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
|
||||||
set MIXER FMU_quad_w
|
set MIXER FMU_quad_w
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
set PWM_OUTPUTS 1234
|
||||||
set PWM_RATE 400
|
|
||||||
set PWM_DISARMED 900
|
|
||||||
set PWM_MIN 1000
|
|
||||||
set PWM_MAX 2000
|
|
||||||
|
|
|
@ -5,6 +5,8 @@
|
||||||
# Anton Babushkin <anton.babushkin@me.com>
|
# Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
sh /etc/init.d/4001_quad_x
|
sh /etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
|
set MIXER FMU_quad_x
|
||||||
|
|
||||||
set HIL yes
|
set HIL yes
|
||||||
|
|
|
@ -5,6 +5,8 @@
|
||||||
# Anton Babushkin <anton.babushkin@me.com>
|
# Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
sh /etc/init.d/1001_rc_quad_x.hil
|
sh /etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
set MIXER FMU_quad_+
|
set MIXER FMU_quad_+
|
||||||
|
|
||||||
|
set HIL yes
|
|
@ -5,38 +5,10 @@
|
||||||
# Thomas Gubler <thomasgubler@gmail.com>
|
# Thomas Gubler <thomasgubler@gmail.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
echo "HIL Rascal 110 starting.."
|
sh /etc/init.d/rc.fw_defaults
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
echo "HIL Rascal 110 starting.."
|
||||||
then
|
|
||||||
# Set all params here, then disable autoconfig
|
|
||||||
|
|
||||||
param set FW_P_D 0
|
|
||||||
param set FW_P_I 0
|
|
||||||
param set FW_P_IMAX 15
|
|
||||||
param set FW_P_LIM_MAX 50
|
|
||||||
param set FW_P_LIM_MIN -50
|
|
||||||
param set FW_P_P 60
|
|
||||||
param set FW_P_RMAX_NEG 0
|
|
||||||
param set FW_P_RMAX_POS 0
|
|
||||||
param set FW_P_ROLLFF 1.1
|
|
||||||
param set FW_R_D 0
|
|
||||||
param set FW_R_I 5
|
|
||||||
param set FW_R_IMAX 20
|
|
||||||
param set FW_R_P 100
|
|
||||||
param set FW_R_RMAX 100
|
|
||||||
param set FW_THR_CRUISE 0.65
|
|
||||||
param set FW_THR_MAX 1
|
|
||||||
param set FW_THR_MIN 0
|
|
||||||
param set FW_T_SINK_MAX 5.0
|
|
||||||
param set FW_T_SINK_MIN 4.0
|
|
||||||
param set FW_Y_ROLLFF 1.1
|
|
||||||
param set FW_L1_PERIOD 16
|
|
||||||
param set RC_SCALE_ROLL 1.0
|
|
||||||
param set RC_SCALE_PITCH 1.0
|
|
||||||
fi
|
|
||||||
|
|
||||||
set HIL yes
|
set HIL yes
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
set MIXER FMU_AERT
|
set MIXER FMU_AERT
|
||||||
|
|
|
@ -5,14 +5,13 @@
|
||||||
# Thomas Gubler <thomasgubler@gmail.com>
|
# Thomas Gubler <thomasgubler@gmail.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
echo "HIL Malolo 1 starting.."
|
sh /etc/init.d/rc.fw_defaults
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
then
|
then
|
||||||
# Set all params here, then disable autoconfig
|
|
||||||
|
|
||||||
param set FW_AIRSPD_MIN 12
|
param set FW_AIRSPD_MIN 12
|
||||||
param set FW_AIRSPD_TRIM 25
|
param set FW_AIRSPD_TRIM 25
|
||||||
|
param set FW_AIRSPD_MAX 40
|
||||||
param set FW_ATT_TC 0.3
|
param set FW_ATT_TC 0.3
|
||||||
param set FW_L1_DAMPING 0.74
|
param set FW_L1_DAMPING 0.74
|
||||||
param set FW_L1_PERIOD 15
|
param set FW_L1_PERIOD 15
|
||||||
|
@ -20,10 +19,6 @@ then
|
||||||
param set FW_PR_I 0.05
|
param set FW_PR_I 0.05
|
||||||
param set FW_PR_IMAX 0.2
|
param set FW_PR_IMAX 0.2
|
||||||
param set FW_PR_P 0.1
|
param set FW_PR_P 0.1
|
||||||
param set FW_P_LIM_MAX 45
|
|
||||||
param set FW_P_LIM_MIN -45
|
|
||||||
param set FW_P_RMAX_NEG 0
|
|
||||||
param set FW_P_RMAX_POS 0
|
|
||||||
param set FW_P_ROLLFF 0
|
param set FW_P_ROLLFF 0
|
||||||
param set FW_RR_FF 0.6
|
param set FW_RR_FF 0.6
|
||||||
param set FW_RR_I 0.02
|
param set FW_RR_I 0.02
|
||||||
|
@ -31,9 +26,6 @@ then
|
||||||
param set FW_RR_P 0.1
|
param set FW_RR_P 0.1
|
||||||
param set FW_R_LIM 45
|
param set FW_R_LIM 45
|
||||||
param set FW_R_RMAX 0
|
param set FW_R_RMAX 0
|
||||||
param set FW_THR_CRUISE 0.6
|
|
||||||
param set FW_THR_MAX 1
|
|
||||||
param set FW_THR_MIN 0
|
|
||||||
param set FW_T_CLMB_MAX 5
|
param set FW_T_CLMB_MAX 5
|
||||||
param set FW_T_HRATE_P 0.02
|
param set FW_T_HRATE_P 0.02
|
||||||
param set FW_T_PTCH_DAMP 0
|
param set FW_T_PTCH_DAMP 0
|
||||||
|
@ -43,22 +35,13 @@ then
|
||||||
param set FW_T_SRATE_P 0.01
|
param set FW_T_SRATE_P 0.01
|
||||||
param set FW_T_TIME_CONST 3
|
param set FW_T_TIME_CONST 3
|
||||||
param set FW_T_VERT_ACC 7
|
param set FW_T_VERT_ACC 7
|
||||||
param set FW_YCO_VMIN 1000
|
|
||||||
param set FW_YR_FF 0.0
|
param set FW_YR_FF 0.0
|
||||||
param set FW_YR_I 0
|
param set FW_YR_I 0
|
||||||
param set FW_YR_IMAX 0.2
|
param set FW_YR_IMAX 0.2
|
||||||
param set FW_YR_P 0.0
|
param set FW_YR_P 0.0
|
||||||
param set FW_Y_RMAX 0
|
|
||||||
param set NAV_LAND_ALT 90
|
|
||||||
param set NAV_RTL_ALT 100
|
|
||||||
param set NAV_RTL_LAND_T -1
|
|
||||||
|
|
||||||
param set SYS_AUTOCONFIG 0
|
|
||||||
param save
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
set HIL yes
|
set HIL yes
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
# Set the AERT mixer for HIL (even if the malolo is a flying wing)
|
# Set the AERT mixer for HIL (even if the malolo is a flying wing)
|
||||||
set MIXER FMU_AERT
|
set MIXER FMU_AERT
|
||||||
|
|
|
@ -5,6 +5,8 @@
|
||||||
# Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
# Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
sh /etc/init.d/8001_octo_x
|
sh /etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
set MIXER FMU_octo_cox
|
set MIXER FMU_octo_cox
|
||||||
|
|
||||||
|
set PWM_OUTPUTS 12345678
|
|
@ -2,38 +2,7 @@
|
||||||
#
|
#
|
||||||
# MPX EasyStar Plane
|
# MPX EasyStar Plane
|
||||||
#
|
#
|
||||||
# Maintainers: ???
|
|
||||||
#
|
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/rc.fw_defaults
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set FW_P_D 0
|
|
||||||
param set FW_P_I 0
|
|
||||||
param set FW_P_IMAX 15
|
|
||||||
param set FW_P_LIM_MAX 50
|
|
||||||
param set FW_P_LIM_MIN -50
|
|
||||||
param set FW_P_P 60
|
|
||||||
param set FW_P_RMAX_NEG 0
|
|
||||||
param set FW_P_RMAX_POS 0
|
|
||||||
param set FW_P_ROLLFF 1.1
|
|
||||||
param set FW_R_D 0
|
|
||||||
param set FW_R_I 5
|
|
||||||
param set FW_R_IMAX 20
|
|
||||||
param set FW_R_P 100
|
|
||||||
param set FW_R_RMAX 100
|
|
||||||
param set FW_THR_CRUISE 0.65
|
|
||||||
param set FW_THR_MAX 1
|
|
||||||
param set FW_THR_MIN 0
|
|
||||||
param set FW_T_SINK_MAX 5.0
|
|
||||||
param set FW_T_SINK_MIN 4.0
|
|
||||||
param set FW_Y_ROLLFF 1.1
|
|
||||||
param set FW_L1_PERIOD 16
|
|
||||||
param set RC_SCALE_ROLL 1.0
|
|
||||||
param set RC_SCALE_PITCH 1.0
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
set MIXER FMU_RET
|
set MIXER FMU_RET
|
||||||
|
|
|
@ -1,35 +1,5 @@
|
||||||
#!nsh
|
#!nsh
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/rc.fw_defaults
|
||||||
then
|
|
||||||
# Set all params here, then disable autoconfig
|
|
||||||
param set FW_P_D 0
|
|
||||||
param set FW_P_I 0
|
|
||||||
param set FW_P_IMAX 15
|
|
||||||
param set FW_P_LIM_MAX 50
|
|
||||||
param set FW_P_LIM_MIN -50
|
|
||||||
param set FW_P_P 60
|
|
||||||
param set FW_P_RMAX_NEG 0
|
|
||||||
param set FW_P_RMAX_POS 0
|
|
||||||
param set FW_P_ROLLFF 1.1
|
|
||||||
param set FW_R_D 0
|
|
||||||
param set FW_R_I 5
|
|
||||||
param set FW_R_IMAX 20
|
|
||||||
param set FW_R_P 100
|
|
||||||
param set FW_R_RMAX 100
|
|
||||||
param set FW_THR_CRUISE 0.65
|
|
||||||
param set FW_THR_MAX 1
|
|
||||||
param set FW_THR_MIN 0
|
|
||||||
param set FW_T_SINK_MAX 5.0
|
|
||||||
param set FW_T_SINK_MIN 4.0
|
|
||||||
param set FW_Y_ROLLFF 1.1
|
|
||||||
param set FW_L1_PERIOD 16
|
|
||||||
param set RC_SCALE_ROLL 1.0
|
|
||||||
param set RC_SCALE_PITCH 1.0
|
|
||||||
|
|
||||||
param set SYS_AUTOCONFIG 0
|
|
||||||
param save
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
set MIXER FMU_AERT
|
set MIXER FMU_AERT
|
|
@ -1,33 +1,5 @@
|
||||||
#!nsh
|
#!nsh
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/rc.fw_defaults
|
||||||
then
|
|
||||||
# Set all params here, then disable autoconfig
|
|
||||||
param set FW_P_D 0
|
|
||||||
param set FW_P_I 0
|
|
||||||
param set FW_P_IMAX 15
|
|
||||||
param set FW_P_LIM_MAX 50
|
|
||||||
param set FW_P_LIM_MIN -50
|
|
||||||
param set FW_P_P 60
|
|
||||||
param set FW_P_RMAX_NEG 0
|
|
||||||
param set FW_P_RMAX_POS 0
|
|
||||||
param set FW_P_ROLLFF 1.1
|
|
||||||
param set FW_R_D 0
|
|
||||||
param set FW_R_I 5
|
|
||||||
param set FW_R_IMAX 20
|
|
||||||
param set FW_R_P 100
|
|
||||||
param set FW_R_RMAX 100
|
|
||||||
param set FW_THR_CRUISE 0.65
|
|
||||||
param set FW_T_SINK_MAX 5.0
|
|
||||||
param set FW_T_SINK_MIN 4.0
|
|
||||||
param set FW_Y_ROLLFF 1.1
|
|
||||||
param set FW_L1_PERIOD 16
|
|
||||||
param set RC_SCALE_ROLL 1.0
|
|
||||||
param set RC_SCALE_PITCH 1.0
|
|
||||||
|
|
||||||
param set SYS_AUTOCONFIG 0
|
|
||||||
param save
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
set MIXER FMU_AERT
|
set MIXER FMU_AERT
|
|
@ -1,38 +1,5 @@
|
||||||
#!nsh
|
#!nsh
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/rc.fw_defaults
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set FW_AIRSPD_MIN 7
|
|
||||||
param set FW_AIRSPD_TRIM 9
|
|
||||||
param set FW_AIRSPD_MAX 14
|
|
||||||
param set FW_L1_PERIOD 10
|
|
||||||
param set FW_P_D 0
|
|
||||||
param set FW_P_I 0
|
|
||||||
param set FW_P_IMAX 20
|
|
||||||
param set FW_P_LIM_MAX 30
|
|
||||||
param set FW_P_LIM_MIN -20
|
|
||||||
param set FW_P_P 30
|
|
||||||
param set FW_P_RMAX_NEG 0
|
|
||||||
param set FW_P_RMAX_POS 0
|
|
||||||
param set FW_P_ROLLFF 2
|
|
||||||
param set FW_R_D 0
|
|
||||||
param set FW_R_I 5
|
|
||||||
param set FW_R_IMAX 20
|
|
||||||
param set FW_R_P 60
|
|
||||||
param set FW_R_RMAX 60
|
|
||||||
param set FW_THR_CRUISE 0.65
|
|
||||||
param set FW_THR_MAX 1.0
|
|
||||||
param set FW_THR_MIN 0
|
|
||||||
param set FW_T_SINK_MAX 5
|
|
||||||
param set FW_T_SINK_MIN 2
|
|
||||||
param set FW_T_TIME_CONST 9
|
|
||||||
param set FW_Y_ROLLFF 2.0
|
|
||||||
param set RC_SCALE_ROLL 1.0
|
|
||||||
param set RC_SCALE_PITCH 1.0
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
set MIXER FMU_Q
|
set MIXER FMU_Q
|
||||||
|
|
|
@ -5,40 +5,4 @@
|
||||||
# Simon Wilks <sjwilks@gmail.com>
|
# Simon Wilks <sjwilks@gmail.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set FW_AIRSPD_MIN 11.4
|
|
||||||
param set FW_AIRSPD_TRIM 14
|
|
||||||
param set FW_AIRSPD_MAX 22
|
|
||||||
param set FW_L1_PERIOD 15
|
|
||||||
param set FW_P_D 0
|
|
||||||
param set FW_P_I 0
|
|
||||||
param set FW_P_IMAX 15
|
|
||||||
param set FW_P_LIM_MAX 45
|
|
||||||
param set FW_P_LIM_MIN -45
|
|
||||||
param set FW_P_P 60
|
|
||||||
param set FW_P_RMAX_NEG 0
|
|
||||||
param set FW_P_RMAX_POS 0
|
|
||||||
param set FW_P_ROLLFF 2
|
|
||||||
param set FW_R_D 0
|
|
||||||
param set FW_R_I 5
|
|
||||||
param set FW_R_IMAX 15
|
|
||||||
param set FW_R_P 80
|
|
||||||
param set FW_R_RMAX 60
|
|
||||||
param set FW_THR_CRUISE 0.8
|
|
||||||
param set FW_THR_LND_MAX 0
|
|
||||||
param set FW_THR_MAX 1
|
|
||||||
param set FW_THR_MIN 0.5
|
|
||||||
param set FW_T_SINK_MAX 5.0
|
|
||||||
param set FW_T_SINK_MIN 2.0
|
|
||||||
param set FW_Y_ROLLFF 1.0
|
|
||||||
param set RC_SCALE_ROLL 0.6
|
|
||||||
param set RC_SCALE_PITCH 0.6
|
|
||||||
param set TRIM_PITCH 0.1
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
set MIXER FMU_Q
|
set MIXER FMU_Q
|
||||||
|
|
|
@ -5,39 +5,35 @@
|
||||||
# Thomas Gubler <thomasgubler@gmail.com>, Julian Oes <joes@student.ethz.ch>
|
# Thomas Gubler <thomasgubler@gmail.com>, Julian Oes <joes@student.ethz.ch>
|
||||||
#
|
#
|
||||||
|
|
||||||
|
sh /etc/init.d/rc.fw_defaults
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
then
|
then
|
||||||
#
|
param set FW_AIRSPD_MIN 15
|
||||||
# Default parameters for this platform
|
param set FW_AIRSPD_TRIM 20
|
||||||
#
|
param set FW_AIRSPD_MAX 40
|
||||||
param set FW_AIRSPD_MIN 7
|
param set FW_ATT_TC 0.3
|
||||||
param set FW_AIRSPD_TRIM 9
|
param set FW_L1_DAMPING 0.74
|
||||||
param set FW_AIRSPD_MAX 14
|
param set FW_L1_PERIOD 15
|
||||||
param set FW_L1_PERIOD 10
|
param set FW_PR_FF 0.3
|
||||||
param set FW_P_D 0
|
param set FW_PR_I 0
|
||||||
param set FW_P_I 0
|
param set FW_PR_IMAX 0.2
|
||||||
param set FW_P_IMAX 20
|
param set FW_PR_P 0.03
|
||||||
param set FW_P_LIM_MAX 30
|
param set FW_P_LIM_MAX 45
|
||||||
param set FW_P_LIM_MIN -20
|
param set FW_P_LIM_MIN -45
|
||||||
param set FW_P_P 30
|
|
||||||
param set FW_P_RMAX_NEG 0
|
param set FW_P_RMAX_NEG 0
|
||||||
param set FW_P_RMAX_POS 0
|
param set FW_P_RMAX_POS 0
|
||||||
param set FW_P_ROLLFF 2
|
param set FW_P_ROLLFF 0
|
||||||
param set FW_R_D 0
|
param set FW_RR_FF 0.3
|
||||||
param set FW_R_I 5
|
param set FW_RR_I 0
|
||||||
param set FW_R_IMAX 20
|
param set FW_RR_IMAX 0.2
|
||||||
param set FW_R_P 60
|
param set FW_RR_P 0.03
|
||||||
param set FW_R_RMAX 60
|
param set FW_R_LIM 60
|
||||||
param set FW_THR_CRUISE 0.65
|
param set FW_R_RMAX 0
|
||||||
param set FW_THR_MAX 0.7
|
param set FW_T_HRATE_P 0.01
|
||||||
param set FW_THR_MIN 0
|
param set FW_T_RLL2THR 15
|
||||||
param set FW_T_SINK_MAX 5
|
param set FW_T_SRATE_P 0.01
|
||||||
param set FW_T_SINK_MIN 2
|
param set FW_T_TIME_CONST 5
|
||||||
param set FW_T_TIME_CONST 9
|
|
||||||
param set FW_Y_ROLLFF 2.0
|
|
||||||
param set RC_SCALE_ROLL 1.0
|
|
||||||
param set RC_SCALE_PITCH 1.0
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
set MIXER FMU_X5
|
set MIXER FMU_X5
|
||||||
|
|
|
@ -5,39 +5,6 @@
|
||||||
# Simon Wilks <sjwilks@gmail.com>
|
# Simon Wilks <sjwilks@gmail.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/rc.fw_defaults
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set FW_AIRSPD_MIN 7
|
|
||||||
param set FW_AIRSPD_TRIM 9
|
|
||||||
param set FW_AIRSPD_MAX 14
|
|
||||||
param set FW_L1_PERIOD 10
|
|
||||||
param set FW_P_D 0
|
|
||||||
param set FW_P_I 0
|
|
||||||
param set FW_P_IMAX 20
|
|
||||||
param set FW_P_LIM_MAX 30
|
|
||||||
param set FW_P_LIM_MIN -20
|
|
||||||
param set FW_P_P 30
|
|
||||||
param set FW_P_RMAX_NEG 0
|
|
||||||
param set FW_P_RMAX_POS 0
|
|
||||||
param set FW_P_ROLLFF 2
|
|
||||||
param set FW_R_D 0
|
|
||||||
param set FW_R_I 5
|
|
||||||
param set FW_R_IMAX 20
|
|
||||||
param set FW_R_P 60
|
|
||||||
param set FW_R_RMAX 60
|
|
||||||
param set FW_THR_CRUISE 0.65
|
|
||||||
param set FW_THR_MAX 0.7
|
|
||||||
param set FW_THR_MIN 0
|
|
||||||
param set FW_T_SINK_MAX 5
|
|
||||||
param set FW_T_SINK_MIN 2
|
|
||||||
param set FW_T_TIME_CONST 9
|
|
||||||
param set FW_Y_ROLLFF 2.0
|
|
||||||
param set RC_SCALE_ROLL 1.0
|
|
||||||
param set RC_SCALE_PITCH 1.0
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
set MIXER FMU_Q
|
set MIXER FMU_Q
|
||||||
|
|
|
@ -5,39 +5,6 @@
|
||||||
# Simon Wilks <sjwilks@gmail.com>
|
# Simon Wilks <sjwilks@gmail.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/rc.fw_defaults
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set FW_AIRSPD_MAX 20
|
|
||||||
param set FW_AIRSPD_TRIM 12
|
|
||||||
param set FW_AIRSPD_MIN 15
|
|
||||||
param set FW_L1_PERIOD 12
|
|
||||||
param set FW_P_D 0
|
|
||||||
param set FW_P_I 0
|
|
||||||
param set FW_P_IMAX 15
|
|
||||||
param set FW_P_LIM_MAX 50
|
|
||||||
param set FW_P_LIM_MIN -50
|
|
||||||
param set FW_P_P 60
|
|
||||||
param set FW_P_RMAX_NEG 0
|
|
||||||
param set FW_P_RMAX_POS 0
|
|
||||||
param set FW_P_ROLLFF 1.1
|
|
||||||
param set FW_R_D 0
|
|
||||||
param set FW_R_I 5
|
|
||||||
param set FW_R_IMAX 20
|
|
||||||
param set FW_R_P 80
|
|
||||||
param set FW_R_RMAX 100
|
|
||||||
param set FW_THR_CRUISE 0.75
|
|
||||||
param set FW_THR_MAX 1
|
|
||||||
param set FW_THR_MIN 0
|
|
||||||
param set FW_T_SINK_MAX 5.0
|
|
||||||
param set FW_T_SINK_MIN 4.0
|
|
||||||
param set FW_T_TIME_CONST 9
|
|
||||||
param set FW_Y_ROLLFF 1.1
|
|
||||||
param set RC_SCALE_ROLL 1.0
|
|
||||||
param set RC_SCALE_PITCH 1.0
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE fw
|
|
||||||
set MIXER FMU_FX79
|
set MIXER FMU_FX79
|
||||||
|
|
|
@ -5,48 +5,8 @@
|
||||||
# Lorenz Meier <lm@inf.ethz.ch>
|
# Lorenz Meier <lm@inf.ethz.ch>
|
||||||
#
|
#
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/rc.mc_defaults
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set MC_ROLL_P 7.0
|
|
||||||
param set MC_ROLLRATE_P 0.12
|
|
||||||
param set MC_ROLLRATE_I 0.0
|
|
||||||
param set MC_ROLLRATE_D 0.004
|
|
||||||
param set MC_PITCH_P 7.0
|
|
||||||
param set MC_PITCHRATE_P 0.12
|
|
||||||
param set MC_PITCHRATE_I 0.0
|
|
||||||
param set MC_PITCHRATE_D 0.004
|
|
||||||
param set MC_YAW_P 2.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_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_TILT_MAX 1.0
|
|
||||||
param set MPC_LAND_SPEED 1.0
|
|
||||||
param set MPC_LAND_TILT 0.3
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
|
||||||
set MIXER FMU_quad_x
|
set MIXER FMU_quad_x
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
set PWM_OUTPUTS 1234
|
||||||
set PWM_RATE 400
|
|
||||||
set PWM_DISARMED 900
|
|
||||||
set PWM_MIN 1100
|
|
||||||
set PWM_MAX 2000
|
|
|
@ -5,49 +5,6 @@
|
||||||
# Anton Babushkin <anton.babushkin@me.com>
|
# Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/4001_quad_x
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set MC_ROLL_P 7.0
|
|
||||||
param set MC_ROLLRATE_P 0.12
|
|
||||||
param set MC_ROLLRATE_I 0.0
|
|
||||||
param set MC_ROLLRATE_D 0.004
|
|
||||||
param set MC_PITCH_P 7.0
|
|
||||||
param set MC_PITCHRATE_P 0.12
|
|
||||||
param set MC_PITCHRATE_I 0.0
|
|
||||||
param set MC_PITCHRATE_D 0.004
|
|
||||||
param set MC_YAW_P 2.8
|
|
||||||
param set MC_YAWRATE_P 0.2
|
|
||||||
param set MC_YAWRATE_I 0.05
|
|
||||||
param set MC_YAWRATE_D 0.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_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_TILT_MAX 1.0
|
|
||||||
param set MPC_LAND_SPEED 1.0
|
|
||||||
param set MPC_LAND_TILT 0.3
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
set PWM_MIN 1175
|
||||||
set MIXER FMU_quad_x
|
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
|
||||||
set PWM_RATE 400
|
|
||||||
# DJI ESC range
|
|
||||||
set PWM_DISARMED 900
|
|
||||||
set PWM_MIN 1200
|
|
||||||
set PWM_MAX 1900
|
|
|
@ -5,49 +5,6 @@
|
||||||
# Lorenz Meier <lm@inf.ethz.ch>
|
# Lorenz Meier <lm@inf.ethz.ch>
|
||||||
#
|
#
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/4001_quad_x
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set MC_ROLL_P 7.0
|
|
||||||
param set MC_ROLLRATE_P 0.12
|
|
||||||
param set MC_ROLLRATE_I 0.0
|
|
||||||
param set MC_ROLLRATE_D 0.004
|
|
||||||
param set MC_PITCH_P 7.0
|
|
||||||
param set MC_PITCHRATE_P 0.12
|
|
||||||
param set MC_PITCHRATE_I 0.0
|
|
||||||
param set MC_PITCHRATE_D 0.004
|
|
||||||
param set MC_YAW_P 2.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_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_TILT_MAX 1.0
|
|
||||||
param set MPC_LAND_SPEED 1.0
|
|
||||||
param set MPC_LAND_TILT 0.3
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
set PWM_MIN 1175
|
||||||
set MIXER FMU_quad_x
|
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
|
||||||
set PWM_RATE 400
|
|
||||||
# DJI ESC range
|
|
||||||
set PWM_DISARMED 900
|
|
||||||
set PWM_MIN 1200
|
|
||||||
set PWM_MAX 1900
|
|
|
@ -6,9 +6,3 @@
|
||||||
#
|
#
|
||||||
|
|
||||||
sh /etc/init.d/4001_quad_x
|
sh /etc/init.d/4001_quad_x
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
|
||||||
set PWM_RATE 400
|
|
||||||
set PWM_DISARMED 900
|
|
||||||
set PWM_MIN 1000
|
|
||||||
set PWM_MAX 2000
|
|
||||||
|
|
|
@ -5,6 +5,8 @@
|
||||||
# Anton Babushkin <anton.babushkin@me.com>
|
# Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
sh /etc/init.d/4001_quad_x
|
sh /etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
set MIXER FMU_quad_+
|
set MIXER FMU_quad_+
|
||||||
|
|
||||||
|
set PWM_OUTPUTS 1234
|
|
@ -5,10 +5,10 @@
|
||||||
# Anton Babushkin <anton.babushkin@me.com>
|
# Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
sh /etc/init.d/4001_quad_x
|
sh /etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
set MIXER FMU_hexa_x
|
set MIXER FMU_hexa_x
|
||||||
|
|
||||||
# We only can run one channel group with one rate,
|
# We only can run one channel group with one rate,
|
||||||
# so all 8 at 400 Hz
|
# so all 8 at 400 Hz
|
||||||
set PWM_OUTPUTS 12345678
|
set PWM_OUTPUTS 12345678
|
|
@ -5,6 +5,10 @@
|
||||||
# Anton Babushkin <anton.babushkin@me.com>
|
# Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
sh /etc/init.d/6001_hexa_x
|
sh /etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
set MIXER FMU_hexa_+
|
set MIXER FMU_hexa_+
|
||||||
|
|
||||||
|
# We only can run one channel group with one rate,
|
||||||
|
# so all 8 at 400 Hz
|
||||||
|
set PWM_OUTPUTS 12345678
|
|
@ -5,8 +5,8 @@
|
||||||
# Anton Babushkin <anton.babushkin@me.com>
|
# Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
sh /etc/init.d/4001_quad_x
|
sh /etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
set MIXER FMU_octo_x
|
set MIXER FMU_octo_x
|
||||||
|
|
||||||
set PWM_OUTPUTS 12345678
|
set PWM_OUTPUTS 12345678
|
|
@ -5,6 +5,8 @@
|
||||||
# Anton Babushkin <anton.babushkin@me.com>
|
# Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
sh /etc/init.d/8001_octo_x
|
sh /etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
set MIXER FMU_octo_+
|
set MIXER FMU_octo_+
|
||||||
|
|
||||||
|
set PWM_OUTPUTS 12345678
|
|
@ -0,0 +1,13 @@
|
||||||
|
#!nsh
|
||||||
|
|
||||||
|
set VEHICLE_TYPE fw
|
||||||
|
|
||||||
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
|
then
|
||||||
|
#
|
||||||
|
# Default parameters for FW
|
||||||
|
#
|
||||||
|
param set NAV_LAND_ALT 90
|
||||||
|
param set NAV_RTL_ALT 100
|
||||||
|
param set NAV_RTL_LAND_T -1
|
||||||
|
fi
|
|
@ -0,0 +1,45 @@
|
||||||
|
#!nsh
|
||||||
|
|
||||||
|
set VEHICLE_TYPE mc
|
||||||
|
|
||||||
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
|
then
|
||||||
|
#
|
||||||
|
# Default parameters for MC
|
||||||
|
#
|
||||||
|
param set MC_ROLL_P 7.0
|
||||||
|
param set MC_ROLLRATE_P 0.12
|
||||||
|
param set MC_ROLLRATE_I 0.0
|
||||||
|
param set MC_ROLLRATE_D 0.004
|
||||||
|
param set MC_PITCH_P 7.0
|
||||||
|
param set MC_PITCHRATE_P 0.12
|
||||||
|
param set MC_PITCHRATE_I 0.0
|
||||||
|
param set MC_PITCHRATE_D 0.004
|
||||||
|
param set MC_YAW_P 2.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_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_TILT_MAX 1.0
|
||||||
|
param set MPC_LAND_SPEED 1.0
|
||||||
|
param set MPC_LAND_TILT 0.3
|
||||||
|
fi
|
||||||
|
|
||||||
|
set PWM_RATE 400
|
||||||
|
set PWM_DISARMED 900
|
||||||
|
set PWM_MIN 1075
|
||||||
|
set PWM_MAX 2000
|
|
@ -464,16 +464,20 @@ then
|
||||||
|
|
||||||
if [ $MIXER == none ]
|
if [ $MIXER == none ]
|
||||||
then
|
then
|
||||||
# Set default mixer for multicopter if not defined
|
echo "Default mixer for multicopter not defined"
|
||||||
set MIXER quad_x
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $MAV_TYPE == none ]
|
if [ $MAV_TYPE == none ]
|
||||||
then
|
then
|
||||||
# Use MAV_TYPE = 2 (quadcopter) if not defined
|
|
||||||
set MAV_TYPE 2
|
|
||||||
|
|
||||||
# Use mixer to detect vehicle type
|
# Use mixer to detect vehicle type
|
||||||
|
if [ $MIXER == FMU_quad_x -o $MIXER == FMU_quad_+ ]
|
||||||
|
then
|
||||||
|
set MAV_TYPE 2
|
||||||
|
fi
|
||||||
|
if [ $MIXER == FMU_quad_w ]
|
||||||
|
then
|
||||||
|
set MAV_TYPE 2
|
||||||
|
fi
|
||||||
if [ $MIXER == FMU_hexa_x -o $MIXER == FMU_hexa_+ ]
|
if [ $MIXER == FMU_hexa_x -o $MIXER == FMU_hexa_+ ]
|
||||||
then
|
then
|
||||||
set MAV_TYPE 13
|
set MAV_TYPE 13
|
||||||
|
@ -487,8 +491,14 @@ then
|
||||||
set MAV_TYPE 14
|
set MAV_TYPE 14
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
param set MAV_TYPE $MAV_TYPE
|
# Still no MAV_TYPE found
|
||||||
|
if [ $MAV_TYPE == none ]
|
||||||
|
then
|
||||||
|
echo "Unknown MAV_TYPE"
|
||||||
|
else
|
||||||
|
param set MAV_TYPE $MAV_TYPE
|
||||||
|
fi
|
||||||
|
|
||||||
# Load mixer and configure outputs
|
# Load mixer and configure outputs
|
||||||
sh /etc/init.d/rc.interface
|
sh /etc/init.d/rc.interface
|
||||||
|
@ -502,10 +512,8 @@ then
|
||||||
#
|
#
|
||||||
if [ $VEHICLE_TYPE == none ]
|
if [ $VEHICLE_TYPE == none ]
|
||||||
then
|
then
|
||||||
echo "[init] Vehicle type: GENERIC"
|
echo "[init] Vehicle type: No autostart ID found"
|
||||||
|
|
||||||
# Load mixer and configure outputs
|
|
||||||
sh /etc/init.d/rc.interface
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# Start any custom addons
|
# Start any custom addons
|
||||||
|
|
|
@ -209,8 +209,8 @@
|
||||||
|
|
||||||
#define GPIO_USART3_RX GPIO_USART3_RX_3
|
#define GPIO_USART3_RX GPIO_USART3_RX_3
|
||||||
#define GPIO_USART3_TX GPIO_USART3_TX_3
|
#define GPIO_USART3_TX GPIO_USART3_TX_3
|
||||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2
|
#define GPIO_USART3_RTS GPIO_USART3_RTS_2
|
||||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_2
|
#define GPIO_USART3_CTS GPIO_USART3_CTS_2
|
||||||
|
|
||||||
#define GPIO_UART4_RX GPIO_UART4_RX_1
|
#define GPIO_UART4_RX GPIO_UART4_RX_1
|
||||||
#define GPIO_UART4_TX GPIO_UART4_TX_1
|
#define GPIO_UART4_TX GPIO_UART4_TX_1
|
||||||
|
|
|
@ -168,7 +168,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
|
||||||
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
|
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
|
||||||
PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f);
|
PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f);
|
||||||
|
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_ANG, 10.0f);
|
PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f);
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_SLLR, 0.9f);
|
PARAM_DEFINE_FLOAT(FW_LND_SLLR, 0.9f);
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f);
|
PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f);
|
||||||
PARAM_DEFINE_FLOAT(FW_LND_FLALT, 15.0f);
|
PARAM_DEFINE_FLOAT(FW_LND_FLALT, 15.0f);
|
||||||
|
|
|
@ -55,7 +55,7 @@
|
||||||
|
|
||||||
PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f);
|
PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f);
|
||||||
PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f);
|
PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f);
|
||||||
PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 100.0f);
|
PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
|
||||||
PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0);
|
PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0);
|
||||||
PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); // default TAKEOFF altitude
|
PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); // default TAKEOFF altitude
|
||||||
PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing
|
PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing
|
||||||
|
|
Loading…
Reference in New Issue