mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 15:17:34 +08:00
Autostart: some fixed wing setups added
This commit is contained in:
@@ -24,9 +24,7 @@ then
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
set FRAME_TYPE mc
|
||||
set VEHICLE_TYPE mc
|
||||
set FRAME_GEOMETRY quad_w
|
||||
|
||||
set PWM_RATE 400
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1100
|
||||
set PWM_MAX 1900
|
||||
|
||||
@@ -1,6 +1,9 @@
|
||||
#!nsh
|
||||
|
||||
echo "[init] EasyStar"
|
||||
#
|
||||
# MPX EasyStar Plane
|
||||
#
|
||||
# Maintainers: ???
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
@@ -32,5 +35,5 @@ then
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
fi
|
||||
|
||||
set FRAME_TYPE fw
|
||||
set VEHICLE_TYPE fw
|
||||
set FRAME_GEOMETRY RET
|
||||
|
||||
@@ -1,85 +0,0 @@
|
||||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on Phantom FPV"
|
||||
|
||||
#
|
||||
# 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 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
|
||||
|
||||
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
|
||||
|
||||
#
|
||||
# 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
|
||||
@@ -0,0 +1,44 @@
|
||||
#!nsh
|
||||
#
|
||||
# Phantom FPV Flying Wing
|
||||
#
|
||||
# Maintainers: 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 FRAME_GEOMETRY Q
|
||||
@@ -1,84 +0,0 @@
|
||||
#!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
|
||||
|
||||
#
|
||||
# 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
|
||||
@@ -0,0 +1,43 @@
|
||||
#!nsh
|
||||
#
|
||||
# Wing Wing (aka Z-84) Flying Wing
|
||||
#
|
||||
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
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 FRAME_GEOMETRY Q
|
||||
@@ -0,0 +1,43 @@
|
||||
#!nsh
|
||||
#
|
||||
# FX-79 Buffalo Flying Wing
|
||||
#
|
||||
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
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 FRAME_GEOMETRY Q
|
||||
@@ -1,84 +0,0 @@
|
||||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on FX-79 Buffalo"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
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
|
||||
|
||||
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
|
||||
|
||||
#
|
||||
# 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_FX79.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_FX79.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_FX79.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_FX79.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_FX79.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
||||
@@ -77,24 +77,24 @@ then
|
||||
#sh /etc/init.d/3030_io_camflyer
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3031 31
|
||||
if param compare SYS_AUTOSTART 3031
|
||||
then
|
||||
#sh /etc/init.d/3031_io_phantom
|
||||
sh /etc/init.d/3031_phantom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3032 32
|
||||
if param compare SYS_AUTOSTART 3032
|
||||
then
|
||||
#sh /etc/init.d/3032_skywalker_x5
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3033 33
|
||||
if param compare SYS_AUTOSTART 3033
|
||||
then
|
||||
#sh /etc/init.d/3033_io_wingwing
|
||||
sh /etc/init.d/3033_wingwing
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3034 34
|
||||
if param compare SYS_AUTOSTART 3034
|
||||
then
|
||||
#sh /etc/init.d/3034_io_fx79
|
||||
sh /etc/init.d/3034_fx79
|
||||
fi
|
||||
|
||||
#
|
||||
|
||||
Reference in New Issue
Block a user