Reworked how start scripts work, relying on io detect now

This commit is contained in:
Lorenz Meier 2013-08-28 14:58:29 +02:00
parent b7ee1d3429
commit 49ef30b834
11 changed files with 35 additions and 100 deletions

View File

@ -25,7 +25,7 @@ then
param set RC_SCALE_YAW 3
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
param save
fi
#

View File

@ -11,7 +11,7 @@ then
# TODO
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
param save
fi
#

View File

@ -11,7 +11,7 @@ then
# TODO
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
param save
fi
#

View File

@ -1,6 +1,6 @@
#!nsh
echo "[init] 10_io_f330: PX4FMU+PX4IO on a DJI F330 quad frame"
echo "[init] PX4FMU v1, v2 with or without IO on DJI F330"
#
# Load default params for this platform
@ -24,7 +24,7 @@ then
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_P 0.3
param save /fs/microsd/params
param save
fi
#
@ -32,24 +32,30 @@ fi
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
# Start MAVLink (depends on orb)
#
mavlink start
usleep 5000
set EXIT_ON_END no
#
# Start and configure PX4IO interface
# Start and configure PX4IO or FMU interface
#
sh /etc/init.d/rc.io
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
usleep 5000
#
# Set PWM values for DJI ESCs
#
px4io idle 900 900 900 900
px4io min 1200 1200 1200 1200
px4io max 1800 1800 1800 1800
sh /etc/init.d/rc.io
# Set PWM values for DJI ESCs
px4io idle 900 900 900 900
px4io min 1200 1200 1200 1200
px4io max 1800 1800 1800 1800
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
usleep 5000
fmu mode_pwm
set EXIT_ON_END yes
fi
#
# Load mixer
@ -65,3 +71,8 @@ pwm -u 400 -m 0xff
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
if [ $EXIT_ON_END == yes ]
then
exit
fi

View File

@ -24,7 +24,7 @@ then
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_P 0.2
param save /fs/microsd/params
param save
fi
#

View File

@ -11,7 +11,7 @@ then
# TODO
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
param save
fi
#

View File

@ -11,7 +11,7 @@ then
# TODO
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
param save
fi
#

View File

@ -9,7 +9,7 @@ then
# TODO
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
param save
fi
#

View File

@ -25,7 +25,7 @@ then
param set RC_SCALE_YAW 3
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
param save
fi
#

View File

@ -1,66 +0,0 @@
#!nsh
#
# If we are still in flight mode, work out what airframe
# configuration we have and start up accordingly.
#
if [ $MODE != autostart ]
then
echo "[init] automatic startup cancelled by user script"
else
echo "[init] detecting attached hardware..."
#
# Assume that we are PX4FMU in standalone mode
#
set BOARD PX4FMU
#
# Are we attached to a PX4IOAR (AR.Drone carrier board)?
#
if boardinfo test name PX4IOAR
then
set BOARD PX4IOAR
if [ -f /etc/init.d/rc.PX4IOAR ]
then
echo "[init] reading /etc/init.d/rc.PX4IOAR"
usleep 500
sh /etc/init.d/rc.PX4IOAR
fi
else
echo "[init] PX4IOAR not detected"
fi
#
# Are we attached to a PX4IO?
#
if boardinfo test name PX4IO
then
set BOARD PX4IO
if [ -f /etc/init.d/rc.PX4IO ]
then
echo "[init] reading /etc/init.d/rc.PX4IO"
usleep 500
sh /etc/init.d/rc.PX4IO
fi
else
echo "[init] PX4IO not detected"
fi
#
# Looks like we are stand-alone
#
if [ $BOARD == PX4FMU ]
then
echo "[init] no expansion board detected"
if [ -f /etc/init.d/rc.standalone ]
then
echo "[init] reading /etc/init.d/rc.standalone"
sh /etc/init.d/rc.standalone
fi
fi
#
# We may not reach here if the airframe-specific script exits the shell.
#
echo "[init] startup done."
fi

View File

@ -13,16 +13,6 @@ mavlink start -b 230400 -d /dev/ttyS1
# Create a fake HIL /dev/pwm_output interface
hil mode_pwm
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
param load /fs/microsd/params
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor