forked from Archive/PX4-Autopilot
Merge pull request #564 from sjwilks/wingwing
Wing Wing (Z-84) startup script
This commit is contained in:
commit
89cc7257a2
|
@ -0,0 +1,91 @@
|
||||||
|
#!nsh
|
||||||
|
|
||||||
|
echo "[init] PX4FMU v1, v2 with or without IO on the Wing Wing (aka Z-84)"
|
||||||
|
|
||||||
|
#
|
||||||
|
# Load default params for this platform
|
||||||
|
#
|
||||||
|
if param compare SYS_AUTOCONFIG 1
|
||||||
|
then
|
||||||
|
# Set all params here, then disable autoconfig
|
||||||
|
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
|
||||||
|
|
||||||
|
param set SYS_AUTOCONFIG 0
|
||||||
|
param save
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Force some key parameters to sane values
|
||||||
|
# MAV_TYPE 1 = fixed wing
|
||||||
|
#
|
||||||
|
param set MAV_TYPE 1
|
||||||
|
|
||||||
|
set EXIT_ON_END no
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start and configure PX4IO or FMU interface
|
||||||
|
#
|
||||||
|
if px4io detect
|
||||||
|
then
|
||||||
|
# Start MAVLink (depends on orb)
|
||||||
|
mavlink start
|
||||||
|
|
||||||
|
sh /etc/init.d/rc.io
|
||||||
|
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||||
|
px4io limit 100
|
||||||
|
else
|
||||||
|
# Start MAVLink (on UART1 / ttyS0)
|
||||||
|
mavlink start -d /dev/ttyS0
|
||||||
|
|
||||||
|
fmu mode_pwm
|
||||||
|
param set BAT_V_SCALING 0.004593
|
||||||
|
set EXIT_ON_END yes
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Load mixer and start controllers (depends on px4io)
|
||||||
|
#
|
||||||
|
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
|
||||||
|
then
|
||||||
|
echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
|
||||||
|
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
|
||||||
|
else
|
||||||
|
echo "Using /etc/mixers/FMU_Q.mix"
|
||||||
|
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start common fixedwing apps
|
||||||
|
#
|
||||||
|
sh /etc/init.d/rc.fixedwing
|
||||||
|
|
||||||
|
if [ $EXIT_ON_END == yes ]
|
||||||
|
then
|
||||||
|
exit
|
||||||
|
fi
|
|
@ -321,6 +321,12 @@ then
|
||||||
set MODE custom
|
set MODE custom
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
if param compare SYS_AUTOSTART 33
|
||||||
|
then
|
||||||
|
sh /etc/init.d/32_io_wingwing
|
||||||
|
set MODE custom
|
||||||
|
fi
|
||||||
|
|
||||||
if param compare SYS_AUTOSTART 40
|
if param compare SYS_AUTOSTART 40
|
||||||
then
|
then
|
||||||
sh /etc/init.d/40_io_segway
|
sh /etc/init.d/40_io_segway
|
||||||
|
|
Loading…
Reference in New Issue