forked from Archive/PX4-Autopilot
Init scripts cleanup, WIP
This commit is contained in:
parent
891cb3f8c2
commit
b5d56523bc
|
@ -1,74 +1,31 @@
|
|||
#!nsh
|
||||
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
|
||||
echo "[init] Team Blacksheep Discovery Quad"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.006
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.17
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 5.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.15
|
||||
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_YAWRATE_D 0.0
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWPOS_I 0.15
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.2
|
||||
|
||||
param save
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load the mixer for a quad with wide arms
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm rate -c 1234 -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 1100
|
||||
pwm max -c 1234 -p 1900
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
set FRAME_TYPE mc
|
||||
set FRAME_GEOMETRY quad_w
|
||||
set PWM_RATE 400
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1100
|
||||
set PWM_MAX 1900
|
||||
|
|
|
@ -1,73 +1,43 @@
|
|||
#!nsh
|
||||
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
|
||||
echo "[init] 3DR Iris Quad"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
# Use generic wide arm quad X PWM as base
|
||||
sh /etc/init.d/10001_quad_w
|
||||
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.13
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 9.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.15
|
||||
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_YAWRATE_D 0.0
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWPOS_I 0.15
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.2
|
||||
|
||||
param save
|
||||
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
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.0098
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load the mixer for a quad with wide arms
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm rate -c 1234 -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 1050
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
|
|
|
@ -37,6 +37,7 @@ then
|
|||
param set MPC_Z_VEL_P 0.20
|
||||
fi
|
||||
|
||||
set FRAME_TYPE mc
|
||||
set FRAME_GEOMETRY x
|
||||
set FRAME_COUNT 4
|
||||
set HIL yes
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set FRAME_GEOMETRY quad_x
|
||||
|
|
|
@ -1,13 +1,12 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on EasyStar"
|
||||
echo "[init] EasyStar"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 15
|
||||
|
@ -31,50 +30,7 @@ then
|
|||
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
|
||||
|
||||
#
|
||||
# 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_RET.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_RET.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_RET.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_RET.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_RET.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
||||
set FRAME_TYPE fw
|
||||
set FRAME_GEOMETRY RET
|
||||
|
|
|
@ -1,17 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>, Lorenz Meier <lm@inf.ethz.ch>
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on generic quadcopter X with PWM ESCs"
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
fi
|
||||
|
||||
set FRAME_TYPE mc
|
||||
set FRAME_GEOMETRY x
|
||||
set FRAME_COUNT 4
|
||||
set PWM_RATE 400
|
|
@ -2,10 +2,7 @@
|
|||
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on DJI F330"
|
||||
|
||||
# Use generic quad X PWM as base
|
||||
sh /etc/init.d/4001_quad_x_pwm
|
||||
echo "[init] DJI F330"
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
|
@ -42,6 +39,11 @@ then
|
|||
param set MPC_Z_VEL_P 0.20
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set FRAME_GEOMETRY quad_x
|
||||
|
||||
set PWM_RATE 400
|
||||
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
|
|
|
@ -2,10 +2,7 @@
|
|||
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on DJI F450"
|
||||
|
||||
# Use generic quad X PWM as base
|
||||
sh /etc/init.d/4001_quad_x_pwm
|
||||
echo "[init] DJI F450"
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
|
@ -27,7 +24,12 @@ then
|
|||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set FRAME_GEOMETRY quad_x
|
||||
|
||||
set PWM_RATE 400
|
||||
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
|
|
|
@ -4,9 +4,6 @@
|
|||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on HobbyKing X550"
|
||||
|
||||
# Use generic quad X PWM as base
|
||||
sh /etc/init.d/4001_quad_x_pwm
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
|
@ -25,3 +22,8 @@ then
|
|||
param set MC_YAWRATE_I 0
|
||||
param set MC_YAWRATE_D 0
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set FRAME_GEOMETRY quad_x
|
||||
|
||||
set PWM_RATE 400
|
||||
|
|
|
@ -1,51 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
# TODO
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 10 = ground rover
|
||||
#
|
||||
param set MAV_TYPE 10
|
||||
|
||||
#
|
||||
# Start MAVLink (depends on orb)
|
||||
#
|
||||
mavlink start -d /dev/ttyS1 -b 57600
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start and configure PX4IO interface
|
||||
#
|
||||
sh /etc/init.d/rc.io
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
attitude_estimator_ekf start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
roboclaw start /dev/ttyS2 128 1200
|
||||
segway start
|
|
@ -1,17 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>, Lorenz Meier <lm@inf.ethz.ch>
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on generic quadcopter + with PWM ESCs"
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
fi
|
||||
|
||||
set FRAME_TYPE mc
|
||||
set FRAME_GEOMETRY +
|
||||
set FRAME_COUNT 4
|
||||
set PWM_RATE 400
|
|
@ -1,17 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>, Lorenz Meier <lm@inf.ethz.ch>
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on generic hexacopter X with PWM ESCs"
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
fi
|
||||
|
||||
set FRAME_TYPE mc
|
||||
set FRAME_GEOMETRY x
|
||||
set FRAME_COUNT 6
|
||||
set PWM_RATE 400
|
|
@ -1,17 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>, Lorenz Meier <lm@inf.ethz.ch>
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on generic hexacopter + with PWM ESCs"
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
fi
|
||||
|
||||
set FRAME_TYPE mc
|
||||
set FRAME_GEOMETRY +
|
||||
set FRAME_COUNT 4
|
||||
set PWM_RATE 400
|
|
@ -1,17 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>, Lorenz Meier <lm@inf.ethz.ch>
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on generic octocopter X with PWM ESCs"
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
fi
|
||||
|
||||
set FRAME_TYPE mc
|
||||
set FRAME_GEOMETRY x
|
||||
set FRAME_COUNT 8
|
||||
set PWM_RATE 400
|
|
@ -1,53 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 init to log only
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Set PWM values for DJI ESCs
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
gps start
|
||||
|
||||
attitude_estimator_ekf start
|
||||
|
||||
position_estimator_inav start
|
||||
|
||||
if [ -d /fs/microsd ]
|
||||
then
|
||||
if hw_ver compare PX4FMU_V1
|
||||
then
|
||||
echo "Start sdlog2 at 50Hz"
|
||||
sdlog2 start -r 50 -e -b 16
|
||||
else
|
||||
echo "Start sdlog2 at 200Hz"
|
||||
sdlog2 start -r 200 -e -b 16
|
||||
fi
|
||||
fi
|
|
@ -1,17 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>, Lorenz Meier <lm@inf.ethz.ch>
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on generic octocopter + with PWM ESCs"
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
fi
|
||||
|
||||
set FRAME_TYPE mc
|
||||
set FRAME_GEOMETRY +
|
||||
set FRAME_COUNT 8
|
||||
set PWM_RATE 400
|
|
@ -17,11 +17,90 @@
|
|||
# 11000 .. 11999 Hexa Cox
|
||||
# 12000 .. 12999 Octo Cox
|
||||
|
||||
if param compare SYS_AUTOSTART 4001
|
||||
#
|
||||
# Simulation setups
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 1000
|
||||
then
|
||||
sh /etc/init.d/4001_quad_x_pwm
|
||||
#sh /etc/init.d/1000_rc_fw_easystar.hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1001
|
||||
then
|
||||
sh /etc/init.d/1001_rc_quad.hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1002
|
||||
then
|
||||
#sh /etc/init.d/1002_rc_fw_state.hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1003
|
||||
then
|
||||
#sh /etc/init.d/1003_rc_quad_+.hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1004
|
||||
then
|
||||
#sh /etc/init.d/1004_rc_fw_Rascal110.hil
|
||||
fi
|
||||
|
||||
#
|
||||
# Standard plane
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 2100 100
|
||||
then
|
||||
#sh /etc/init.d/2100_mpx_easystar
|
||||
#set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2101 101
|
||||
then
|
||||
#sh /etc/init.d/2101_hk_bixler
|
||||
#set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2102 102
|
||||
then
|
||||
#sh /etc/init.d/2102_3dr_skywalker
|
||||
#set MODE custom
|
||||
fi
|
||||
|
||||
#
|
||||
# Flying wing
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 3030
|
||||
then
|
||||
#sh /etc/init.d/3030_io_camflyer
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3031 31
|
||||
then
|
||||
#sh /etc/init.d/3031_io_phantom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3032 32
|
||||
then
|
||||
#sh /etc/init.d/3032_skywalker_x5
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3033 33
|
||||
then
|
||||
#sh /etc/init.d/3033_io_wingwing
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3034 34
|
||||
then
|
||||
#sh /etc/init.d/3034_io_fx79
|
||||
fi
|
||||
|
||||
#
|
||||
# Quad X
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 4008
|
||||
then
|
||||
#sh /etc/init.d/4008_ardrone
|
||||
|
@ -47,135 +126,16 @@ then
|
|||
sh /etc/init.d/4012_hk_x550
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 6001
|
||||
#
|
||||
# Wide arm / H frame
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 10015
|
||||
then
|
||||
sh /etc/init.d/6001_hexa_x_pwm
|
||||
sh /etc/init.d/10015_tbs_discovery
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 7001
|
||||
if param compare SYS_AUTOSTART 10016
|
||||
then
|
||||
sh /etc/init.d/7001_hexa_+_pwm
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 8001
|
||||
then
|
||||
sh /etc/init.d/8001_octo_x_pwm
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 9001
|
||||
then
|
||||
sh /etc/init.d/9001_octo_+_pwm
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 12001
|
||||
then
|
||||
#set MIXER /etc/mixers/FMU_octo_cox.mix
|
||||
#sh /etc/init.d/rc.octo
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10015 15
|
||||
then
|
||||
#sh /etc/init.d/10015_tbs_discovery
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10016 16
|
||||
then
|
||||
#sh /etc/init.d/10016_3dr_iris
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4017 17
|
||||
then
|
||||
#set MKBLCTRL_MODE no
|
||||
#set MKBLCTRL_FRAME x
|
||||
#sh /etc/init.d/rc.custom_dji_f330_mkblctrl
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 5018 18
|
||||
then
|
||||
#set MKBLCTRL_MODE no
|
||||
#set MKBLCTRL_FRAME +
|
||||
#sh /etc/init.d/rc.custom_dji_f330_mkblctrl
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4019 19
|
||||
then
|
||||
#set MKBLCTRL_MODE yes
|
||||
#set MKBLCTRL_FRAME x
|
||||
#sh /etc/init.d/rc.custom_dji_f330_mkblctrl
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 5020 20
|
||||
then
|
||||
#set MKBLCTRL_MODE yes
|
||||
#set MKBLCTRL_FRAME +
|
||||
#sh /etc/init.d/rc.custom_dji_f330_mkblctrl
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4021 21
|
||||
then
|
||||
#set FRAME_GEOMETRY x
|
||||
#set ESC_MAKER afro
|
||||
#sh /etc/init.d/rc.custom_io_esc
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10022 22
|
||||
then
|
||||
#set FRAME_GEOMETRY w
|
||||
#sh /etc/init.d/rc.custom_io_esc
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3030 30
|
||||
then
|
||||
#sh /etc/init.d/3030_io_camflyer
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3031 31
|
||||
then
|
||||
#sh /etc/init.d/3031_io_phantom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3032 32
|
||||
then
|
||||
#sh /etc/init.d/3032_skywalker_x5
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3033 33
|
||||
then
|
||||
#sh /etc/init.d/3033_io_wingwing
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3034 34
|
||||
then
|
||||
#sh /etc/init.d/3034_io_fx79
|
||||
#set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 40
|
||||
then
|
||||
#sh /etc/init.d/40_io_segway
|
||||
#set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2100 100
|
||||
then
|
||||
#sh /etc/init.d/2100_mpx_easystar
|
||||
#set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2101 101
|
||||
then
|
||||
#sh /etc/init.d/2101_hk_bixler
|
||||
#set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2102 102
|
||||
then
|
||||
#sh /etc/init.d/2102_3dr_skywalker
|
||||
#set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 800
|
||||
then
|
||||
#sh /etc/init.d/800_sdlogger
|
||||
#set MODE custom
|
||||
sh /etc/init.d/10016_3dr_iris
|
||||
fi
|
||||
|
|
|
@ -1,34 +0,0 @@
|
|||
#
|
||||
# Check if auto-setup from one of the standard scripts for HIL is wanted
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 1000
|
||||
then
|
||||
#sh /etc/init.d/1000_rc_fw_easystar.hil
|
||||
set MODE hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1001
|
||||
then
|
||||
sh /etc/init.d/1001_rc_quad.hil
|
||||
set MODE hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1002
|
||||
then
|
||||
#sh /etc/init.d/1002_rc_fw_state.hil
|
||||
set MODE hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1003
|
||||
then
|
||||
#sh /etc/init.d/1003_rc_quad_+.hil
|
||||
set MODE hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1004
|
||||
then
|
||||
#sh /etc/init.d/1004_rc_fw_Rascal110.hil
|
||||
set MODE hil
|
||||
fi
|
||||
|
|
@ -1,113 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.002
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.09
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_P 6.8
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWRATE_D 0.005
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set NAV_TAKEOFF_ALT 3.0
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.7
|
||||
param set MPC_THR_MIN 0.3
|
||||
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 save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# Start the Mikrokopter ESC driver
|
||||
#
|
||||
if [ $MKBLCTRL_MODE == yes ]
|
||||
then
|
||||
if [ $MKBLCTRL_FRAME == x ]
|
||||
then
|
||||
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing"
|
||||
mkblctrl -mkmode x
|
||||
else
|
||||
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing"
|
||||
mkblctrl -mkmode +
|
||||
fi
|
||||
else
|
||||
if [ $MKBLCTRL_FRAME == x ]
|
||||
then
|
||||
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame"
|
||||
else
|
||||
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame"
|
||||
fi
|
||||
mkblctrl
|
||||
fi
|
||||
|
||||
usleep 10000
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
if [ $MKBLCTRL_FRAME == x ]
|
||||
then
|
||||
mixer load /dev/mkblctrl /etc/mixers/FMU_quad_x.mix
|
||||
else
|
||||
mixer load /dev/mkblctrl /etc/mixers/FMU_quad_+.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,120 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.002
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.09
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_P 6.8
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWRATE_D 0.005
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set NAV_TAKEOFF_ALT 3.0
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.7
|
||||
param set MPC_THR_MIN 0.3
|
||||
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 save
|
||||
fi
|
||||
|
||||
echo "RC script for PX4FMU + PX4IO + PPM-ESCs running"
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
usleep 10000
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start -d /dev/ttyS1 -b 57600
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
fmu mode_pwm
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS1 -b 57600
|
||||
usleep 5000
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
if [ $ESC_MAKER = afro ]
|
||||
then
|
||||
# Set PWM values for Afro ESCs
|
||||
pwm disarmed -c 1234 -p 1050
|
||||
pwm min -c 1234 -p 1080
|
||||
pwm max -c 1234 -p 1860
|
||||
else
|
||||
# Set PWM values for typical ESCs
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 980
|
||||
pwm max -c 1234 -p 1800
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
if [ $FRAME_GEOMETRY == x ]
|
||||
then
|
||||
echo "Frame geometry X"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
else
|
||||
if [ $FRAME_GEOMETRY == w ]
|
||||
then
|
||||
echo "Frame geometry W"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
|
||||
else
|
||||
echo "Frame geometry +"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm rate -r 400 -c 1234
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
||||
|
||||
echo "Script end"
|
|
@ -1,34 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard everything needed for fixedwing except mixer, actuator output and mavlink
|
||||
#
|
||||
|
||||
#
|
||||
# Start the sensors and test them.
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start logging (depends on sensors)
|
||||
#
|
||||
sh /etc/init.d/rc.logging
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude and position estimator
|
||||
#
|
||||
att_pos_estimator_ekf start
|
||||
|
||||
#
|
||||
# Start attitude controller
|
||||
#
|
||||
fw_att_control start
|
||||
|
||||
#
|
||||
# Start the position controller
|
||||
#
|
||||
fw_pos_control_l1 start
|
|
@ -0,0 +1,19 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard apps for fixed wing
|
||||
#
|
||||
|
||||
#
|
||||
# Start the attitude and position estimator
|
||||
#
|
||||
att_pos_estimator_ekf start
|
||||
|
||||
#
|
||||
# Start attitude controller
|
||||
#
|
||||
fw_att_control start
|
||||
|
||||
#
|
||||
# Start the position controller
|
||||
#
|
||||
fw_pos_control_l1 start
|
|
@ -0,0 +1,18 @@
|
|||
#!nsh
|
||||
#
|
||||
# Script to load fixedwing mixer and set rate/disarmed/min/max values for PWM output
|
||||
#
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
echo "Frame geometry: ${FRAME_GEOMETRY}"
|
||||
set MIXER /etc/mixers/FMU_${FRAME_GEOMETRY}.mix
|
||||
echo "Loading mixer: ${MIXER}"
|
||||
mixer load /dev/pwm_output ${MIXER}
|
|
@ -1,6 +1,6 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard everything needed for multirotors except mixer, actuator output and mavlink
|
||||
# Standard apps for multirotors
|
||||
#
|
||||
|
||||
#
|
||||
|
|
|
@ -1,24 +1,25 @@
|
|||
#!nsh
|
||||
#
|
||||
# Script to set PWM min / max limits and mixer
|
||||
# Script to load multicopter mixer and set rate/disarmed/min/max values for PWM output
|
||||
#
|
||||
|
||||
echo "Rotors count: $FRAME_COUNT"
|
||||
if [ $FRAME_COUNT == 4 ]
|
||||
if [ $FRAME_GEOMETRY == quad_x -o $FRAME_GEOMETRY == quad_+ ]
|
||||
then
|
||||
set FRAME_COUNT_STR quad
|
||||
set OUTPUTS 1234
|
||||
param set MAV_TYPE 2
|
||||
fi
|
||||
if [ $FRAME_COUNT == 6 ]
|
||||
if [ $FRAME_GEOMETRY == quad_w -o $FRAME_GEOMETRY == quad_v ]
|
||||
then
|
||||
set OUTPUTS 1234
|
||||
param set MAV_TYPE 2
|
||||
fi
|
||||
if [ $FRAME_GEOMETRY == hex_x -o $FRAME_GEOMETRY == hex_+ ]
|
||||
then
|
||||
set FRAME_COUNT_STR hex
|
||||
set OUTPUTS 123456
|
||||
param set MAV_TYPE 13
|
||||
fi
|
||||
if [ $FRAME_COUNT == 8 ]
|
||||
if [ $FRAME_GEOMETRY == octo_x -o $FRAME_GEOMETRY == octo_+ ]
|
||||
then
|
||||
set FRAME_COUNT_STR octo
|
||||
set OUTPUTS 12345678
|
||||
param set MAV_TYPE 14
|
||||
fi
|
||||
|
@ -26,31 +27,34 @@ fi
|
|||
#
|
||||
# Load mixer
|
||||
#
|
||||
echo "Frame geometry: ${FRAME_GEOMETRY}"
|
||||
set MIXER /etc/mixers/FMU_${FRAME_GEOMETRY_STR}_${FRAME_GEOMETRY}.mix
|
||||
echo "Loading mixer: ${MIXER}"
|
||||
mixer load /dev/pwm_output ${MIXER}
|
||||
echo "Frame geometry: $FRAME_GEOMETRY"
|
||||
set MIXER /etc/mixers/FMU_${FRAME_GEOMETRY}.mix
|
||||
echo "Loading mixer: $MIXER"
|
||||
mixer load /dev/pwm_output $MIXER
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
if [ $PWM_RATE != none ]
|
||||
if [ $OUTPUT_MODE == fmu_pwm -o $OUTPUT_MODE == io_pwm ]
|
||||
then
|
||||
pwm rate -c $OUTPUTS -r $PWM_RATE
|
||||
fi
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM values
|
||||
#
|
||||
if [ $PWM_DISARMED != none ]
|
||||
then
|
||||
pwm disarmed -c $OUTPUTS -p $PWM_DISARMED
|
||||
fi
|
||||
if [ $PWM_MIN != none ]
|
||||
then
|
||||
pwm min -c $OUTPUTS -p $PWM_MIN
|
||||
fi
|
||||
if [ $PWM_MAX != none ]
|
||||
then
|
||||
pwm max -c $OUTPUTS -p $PWM_MAX
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
if [ $PWM_RATE != none ]
|
||||
then
|
||||
pwm rate -c $OUTPUTS -r $PWM_RATE
|
||||
fi
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM values
|
||||
#
|
||||
if [ $PWM_DISARMED != none ]
|
||||
then
|
||||
pwm disarmed -c $OUTPUTS -p $PWM_DISARMED
|
||||
fi
|
||||
if [ $PWM_MIN != none ]
|
||||
then
|
||||
pwm min -c $OUTPUTS -p $PWM_MIN
|
||||
fi
|
||||
if [ $PWM_MAX != none ]
|
||||
then
|
||||
pwm max -c $OUTPUTS -p $PWM_MAX
|
||||
fi
|
||||
fi
|
||||
|
|
|
@ -1,94 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] Octorotor startup"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWRATE_D 0.005
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set NAV_TAKEOFF_ALT 3.0
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.7
|
||||
param set MPC_THR_MIN 0.3
|
||||
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 save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE list: https://pixhawk.ethz.ch/mavlink/
|
||||
# 14 = octorotor
|
||||
#
|
||||
param set MAV_TYPE 14
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# Start and configure PX4IO interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# This is not possible on an octo
|
||||
tone_alarm error
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
mixer load /dev/pwm_output $MIXER
|
||||
|
||||
#
|
||||
# Set PWM output frequency to 400 Hz
|
||||
#
|
||||
pwm rate -a -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
pwm disarmed -c 12345678 -p 900
|
||||
pwm min -c 12345678 -p 1100
|
||||
pwm max -c 12345678 -p 1900
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,13 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# Flight startup script for PX4FMU standalone configuration.
|
||||
#
|
||||
|
||||
echo "[init] doing standalone PX4FMU startup..."
|
||||
|
||||
#
|
||||
# Start the ORB
|
||||
#
|
||||
uorb start
|
||||
|
||||
echo "[init] startup done"
|
|
@ -36,39 +36,6 @@ then
|
|||
echo "Commander started"
|
||||
fi
|
||||
|
||||
# Start px4io if present
|
||||
if px4io start
|
||||
then
|
||||
echo "PX4IO driver started"
|
||||
else
|
||||
if fmu mode_serial
|
||||
then
|
||||
echo "FMU driver started"
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start sensors
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
# Start one of the estimators
|
||||
if attitude_estimator_ekf status
|
||||
then
|
||||
echo "multicopter att filter running"
|
||||
else
|
||||
if att_pos_estimator_ekf status
|
||||
then
|
||||
echo "fixedwing att filter running"
|
||||
else
|
||||
attitude_estimator_ekf start
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start GPS
|
||||
if gps start
|
||||
then
|
||||
echo "GPS started"
|
||||
fi
|
||||
|
||||
echo "MAVLink started, exiting shell.."
|
||||
|
||||
# Exit shell to make it available to MAVLink
|
||||
|
|
|
@ -52,7 +52,7 @@ then
|
|||
echo "[init] USB interface connected"
|
||||
fi
|
||||
|
||||
echo "Running rc.APM"
|
||||
echo "[init] Running rc.APM"
|
||||
# if APM startup is successful then nsh will exit
|
||||
sh /etc/init.d/rc.APM
|
||||
fi
|
||||
|
@ -85,9 +85,9 @@ then
|
|||
then
|
||||
if param load /fs/microsd/params
|
||||
then
|
||||
echo "Parameters loaded"
|
||||
echo "[init] Parameters loaded"
|
||||
else
|
||||
echo "Parameter file corrupt - ignoring"
|
||||
echo "[init] Parameter file corrupt - ignoring"
|
||||
fi
|
||||
fi
|
||||
#fi
|
||||
|
@ -97,7 +97,7 @@ then
|
|||
#
|
||||
if rgbled start
|
||||
then
|
||||
echo "Using external RGB Led"
|
||||
echo "[init] Using external RGB Led"
|
||||
else
|
||||
if blinkm start
|
||||
then
|
||||
|
@ -105,13 +105,75 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
set USE_IO no
|
||||
# Use FMU PWM output by default
|
||||
set OUTPUT_MODE fmu_pwm
|
||||
set IO_PRESENT no
|
||||
|
||||
#
|
||||
# Upgrade PX4IO firmware
|
||||
#
|
||||
if [ -f /etc/extras/px4io-v2_default.bin ]
|
||||
then
|
||||
set io_file /etc/extras/px4io-v2_default.bin
|
||||
else
|
||||
set io_file /etc/extras/px4io-v1_default.bin
|
||||
fi
|
||||
|
||||
if px4io checkcrc $io_file
|
||||
then
|
||||
echo "[init] PX4IO CRC OK"
|
||||
echo "PX4IO CRC OK" >> $logfile
|
||||
|
||||
set IO_PRESENT yes
|
||||
|
||||
# If PX4IO present, use it as primary PWM output by default
|
||||
set OUTPUT_MODE io_pwm
|
||||
else
|
||||
echo "[init] PX4IO CRC failure"
|
||||
echo "PX4IO CRC failure" >> $logfile
|
||||
tone_alarm MBABGP
|
||||
if px4io forceupdate 14662 $io_file
|
||||
then
|
||||
usleep 500000
|
||||
if px4io start
|
||||
then
|
||||
echo "[init] PX4IO restart OK"
|
||||
echo "PX4IO restart OK" >> $logfile
|
||||
tone_alarm MSPAA
|
||||
|
||||
set IO_PRESENT yes
|
||||
|
||||
# If PX4IO present, use it as primary PWM output by default
|
||||
set OUTPUT_MODE io_pwm
|
||||
else
|
||||
echo "[init] PX4IO restart failed"
|
||||
echo "PX4IO restart failed" >> $logfile
|
||||
if hw_ver compare PX4FMU_V2
|
||||
then
|
||||
tone_alarm MNGGG
|
||||
sleep 10
|
||||
reboot
|
||||
fi
|
||||
fi
|
||||
else
|
||||
echo "[init] PX4IO update failed"
|
||||
echo "PX4IO update failed" >> $logfile
|
||||
if hw_ver compare PX4FMU_V2
|
||||
then
|
||||
tone_alarm MNGGG
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
set HIL no
|
||||
set FRAME_TYPE none
|
||||
set PWM_RATE none
|
||||
set PWM_DISARMED none
|
||||
set PWM_MIN none
|
||||
set PWM_MAX none
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
set DO_AUTOCONFIG yes
|
||||
|
@ -125,112 +187,23 @@ then
|
|||
commander start
|
||||
|
||||
#
|
||||
# Set parameters and env variables for selected AUTOSTART (HIL setups)
|
||||
# Set parameters and env variables for selected AUTOSTART
|
||||
#
|
||||
sh /etc/init.d/rc.autostart_hil
|
||||
|
||||
if [ $MODE == hil ]
|
||||
then
|
||||
#
|
||||
# Do common HIL setup depending on env variables
|
||||
#
|
||||
# Allow USB some time to come up
|
||||
sleep 1
|
||||
sh /etc/init.d/rc.autostart
|
||||
|
||||
# Start MAVLink on USB port
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
usleep 5000
|
||||
|
||||
# Create a fake HIL /dev/pwm_output interface
|
||||
hil mode_pwm
|
||||
|
||||
# Sensors
|
||||
echo "Start sensors"
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Fixed wing setup
|
||||
#
|
||||
if [ $FRAME_TYPE == fw ]
|
||||
then
|
||||
echo "Setup FIXED WING"
|
||||
fi
|
||||
|
||||
#
|
||||
# Multicopters setup
|
||||
#
|
||||
if [ $FRAME_TYPE == mc ]
|
||||
then
|
||||
echo "Setup MULTICOPTER"
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.mc_interface
|
||||
|
||||
# Start common multicopter apps
|
||||
sh /etc/init.d/rc.mc_apps
|
||||
fi
|
||||
# Custom configuration
|
||||
if [ -f /fs/microsd/etc/rc.conf ]
|
||||
then
|
||||
sh /fs/microsd/etc/rc.conf
|
||||
fi
|
||||
|
||||
if [ $HIL == yes ]
|
||||
then
|
||||
set OUTPUT_MODE hil
|
||||
else
|
||||
# Try to get an USB console if not in HIL mode
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
||||
|
||||
#
|
||||
# Upgrade PX4IO firmware
|
||||
#
|
||||
if [ -f /etc/extras/px4io-v2_default.bin ]
|
||||
then
|
||||
set io_file /etc/extras/px4io-v2_default.bin
|
||||
else
|
||||
set io_file /etc/extras/px4io-v1_default.bin
|
||||
fi
|
||||
|
||||
if px4io start
|
||||
then
|
||||
echo "PX4IO OK"
|
||||
echo "PX4IO OK" >> $logfile
|
||||
fi
|
||||
|
||||
if px4io checkcrc $io_file
|
||||
then
|
||||
echo "PX4IO CRC OK"
|
||||
echo "PX4IO CRC OK" >> $logfile
|
||||
set USE_IO yes
|
||||
else
|
||||
echo "PX4IO CRC failure"
|
||||
echo "PX4IO CRC failure" >> $logfile
|
||||
tone_alarm MBABGP
|
||||
if px4io forceupdate 14662 $io_file
|
||||
then
|
||||
usleep 500000
|
||||
if px4io start
|
||||
then
|
||||
echo "PX4IO restart OK"
|
||||
echo "PX4IO restart OK" >> $logfile
|
||||
tone_alarm MSPAA
|
||||
set USE_IO yes
|
||||
else
|
||||
echo "PX4IO restart failed"
|
||||
echo "PX4IO restart failed" >> $logfile
|
||||
if hw_ver compare PX4FMU_V2
|
||||
then
|
||||
tone_alarm MNGGG
|
||||
sleep 10
|
||||
reboot
|
||||
fi
|
||||
fi
|
||||
else
|
||||
echo "PX4IO update failed"
|
||||
echo "PX4IO update failed" >> $logfile
|
||||
tone_alarm MNGGG
|
||||
fi
|
||||
fi
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# Set parameters and env variables for selected AUTOSTART
|
||||
#
|
||||
sh /etc/init.d/rc.autostart
|
||||
|
||||
#
|
||||
# If autoconfig parameter was set, reset it and save parameters
|
||||
|
@ -240,66 +213,132 @@ then
|
|||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
|
||||
if [ $MODE == autostart ]
|
||||
then
|
||||
#
|
||||
# Do common setup depending on env variables
|
||||
# Start primary output
|
||||
#
|
||||
if [ $USE_IO == yes ]
|
||||
if [ $OUTPUT_MODE == io_pwm ]
|
||||
then
|
||||
echo "Use IO"
|
||||
|
||||
# Start MAVLink on default port: ttyS1
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
echo "Don't use IO"
|
||||
|
||||
# Start MAVLink on ttyS0
|
||||
echo "[init] Use PX4IO PWM as primary output"
|
||||
if px4io start
|
||||
then
|
||||
echo "[init] PX4IO OK"
|
||||
echo "PX4IO OK" >> $logfile
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
echo "[init] PX4IO start error"
|
||||
echo "PX4IO start error" >> $logfile
|
||||
tone_alarm MNGGG
|
||||
fi
|
||||
fi
|
||||
if [ $OUTPUT_MODE == fmu_pwm ]
|
||||
then
|
||||
echo "[init] Use PX4FMU PWM as primary output"
|
||||
fmu mode_pwm
|
||||
fi
|
||||
if [ $OUTPUT_MODE == mkblctrl ]
|
||||
then
|
||||
echo "[init] Use MKBLCTRL as primary output"
|
||||
mkblctrl
|
||||
fi
|
||||
if [ $OUTPUT_MODE == hil ]
|
||||
then
|
||||
echo "[init] Use HIL as primary output"
|
||||
hil mode_pwm
|
||||
fi
|
||||
|
||||
#
|
||||
# Start PX4IO as secondary output if needed
|
||||
#
|
||||
if [ $IO_PRESENT == yes -a $OUTPUT_MODE != io_pwm ]
|
||||
then
|
||||
echo "[init] Use PX4IO PWM as secondary output"
|
||||
if px4io start
|
||||
then
|
||||
echo "[init] PX4IO OK"
|
||||
echo "PX4IO OK" >> $logfile
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
echo "[init] PX4IO start error"
|
||||
echo "PX4IO start error" >> $logfile
|
||||
tone_alarm MNGGG
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# MAVLink
|
||||
#
|
||||
if [ $OUTPUT_MODE == fmu_pwm -a hw_ver compare PX4FMU_V1 ]
|
||||
then
|
||||
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as PWM output
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
|
||||
# Configure FMU for PWM outputs
|
||||
fmu mode_pwm
|
||||
|
||||
# Exit from nsh to free port for mavlink
|
||||
set EXIT_ON_END yes
|
||||
else
|
||||
# Start MAVLink on default port: ttyS1
|
||||
mavlink start
|
||||
usleep 5000
|
||||
fi
|
||||
|
||||
# Sensors
|
||||
echo "Start sensors"
|
||||
#
|
||||
# Sensors, Logging, GPS
|
||||
#
|
||||
echo "[init] Start sensors"
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
# Logging
|
||||
sh /etc/init.d/rc.logging
|
||||
|
||||
# GPS interface
|
||||
gps start
|
||||
|
||||
if [ $HIL == no ]
|
||||
then
|
||||
echo "[init] Start logging"
|
||||
sh /etc/init.d/rc.logging
|
||||
fi
|
||||
|
||||
if [ $HIL == no ]
|
||||
then
|
||||
echo "[init] Start GPS"
|
||||
gps start
|
||||
fi
|
||||
|
||||
#
|
||||
# Fixed wing setup
|
||||
#
|
||||
if [ $FRAME_TYPE == fw ]
|
||||
if [ $VEHICLE_TYPE == fw ]
|
||||
then
|
||||
echo "Setup FIXED WING"
|
||||
echo "[init] Vehicle type: FIXED WING"
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.fw_interface
|
||||
|
||||
# Start standard fixedwing apps
|
||||
sh /etc/init.d/rc.mc_apps
|
||||
fi
|
||||
|
||||
#
|
||||
# Multicopters setup
|
||||
#
|
||||
if [ $FRAME_TYPE == mc ]
|
||||
if [ $VEHICLE_TYPE == mc ]
|
||||
then
|
||||
echo "Setup MULTICOPTER"
|
||||
echo "[init] Vehicle type: MULTICOPTER"
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.mc_interface
|
||||
|
||||
# Start common multicopter apps
|
||||
# Start standard multicopter apps
|
||||
sh /etc/init.d/rc.mc_apps
|
||||
fi
|
||||
|
||||
#
|
||||
# Generic setup (autostart ID not found)
|
||||
#
|
||||
if [ $VEHICLE_TYPE == none ]
|
||||
then
|
||||
echo "[init] Vehicle type: GENERIC"
|
||||
attitude_estimator_ekf start
|
||||
position_estimator_inav start
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start any custom extensions
|
||||
|
@ -307,39 +346,6 @@ then
|
|||
then
|
||||
sh /fs/microsd/etc/rc.local
|
||||
fi
|
||||
|
||||
# If none of the autostart scripts triggered, get a minimal setup
|
||||
if [ $MODE == autostart ]
|
||||
then
|
||||
# Telemetry port is on both FMU boards ttyS1
|
||||
# but the AR.Drone motors can be get 'flashed'
|
||||
# if starting MAVLink on them - so do not
|
||||
# start it as default (default link: USB)
|
||||
|
||||
# Start commander
|
||||
commander start
|
||||
|
||||
# Start px4io if present
|
||||
if px4io detect
|
||||
then
|
||||
px4io start
|
||||
else
|
||||
if fmu mode_serial
|
||||
then
|
||||
echo "FMU driver (no PWM) started"
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start sensors
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
# Start one of the estimators
|
||||
attitude_estimator_ekf start
|
||||
|
||||
# Start GPS
|
||||
gps start
|
||||
|
||||
fi
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
|
|
Loading…
Reference in New Issue