2012-08-04 19:12:36 -03:00
|
|
|
#!nsh
|
|
|
|
|
2012-12-06 17:35:20 -04:00
|
|
|
set USB no
|
2012-08-04 19:12:36 -03:00
|
|
|
|
|
|
|
#
|
2012-12-06 17:35:20 -04:00
|
|
|
# Start the object request broker
|
2012-08-04 19:12:36 -03:00
|
|
|
#
|
|
|
|
uorb start
|
|
|
|
|
2012-10-30 03:19:58 -03:00
|
|
|
#
|
|
|
|
# Init the EEPROM
|
|
|
|
#
|
|
|
|
echo "[init] eeprom"
|
|
|
|
eeprom start
|
|
|
|
if [ -f /eeprom/parameters ]
|
|
|
|
then
|
|
|
|
param load
|
|
|
|
fi
|
|
|
|
|
2012-12-06 17:35:20 -04:00
|
|
|
#
|
|
|
|
# Enable / connect to PX4IO
|
|
|
|
#
|
|
|
|
px4io start
|
|
|
|
|
2012-08-04 19:12:36 -03:00
|
|
|
#
|
|
|
|
# Start the sensors.
|
|
|
|
#
|
|
|
|
sh /etc/init.d/rc.sensors
|
|
|
|
|
|
|
|
#
|
2012-12-06 17:35:20 -04:00
|
|
|
# Start MAVLink on UART1 (dev/ttyS0) at 57600 baud (CLI is now unusable)
|
2012-08-04 19:12:36 -03:00
|
|
|
#
|
2012-08-19 11:32:54 -03:00
|
|
|
mavlink start -d /dev/ttyS0 -b 57600
|
2012-12-06 17:35:20 -04:00
|
|
|
usleep 5000
|
2012-08-04 19:12:36 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# Start the commander.
|
|
|
|
#
|
2012-10-30 03:19:58 -03:00
|
|
|
commander start
|
2012-08-04 19:12:36 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# Start the attitude estimator
|
|
|
|
#
|
2012-10-30 03:19:58 -03:00
|
|
|
attitude_estimator_ekf start
|
2012-08-04 19:12:36 -03:00
|
|
|
|
|
|
|
#
|
2012-12-06 17:35:20 -04:00
|
|
|
# Start the attitude and position controller
|
2012-08-04 19:12:36 -03:00
|
|
|
#
|
2012-12-06 17:35:20 -04:00
|
|
|
fixedwing_att_control start
|
|
|
|
fixedwing_pos_control start
|
2012-08-04 19:12:36 -03:00
|
|
|
|
|
|
|
#
|
2012-12-06 17:35:20 -04:00
|
|
|
# Start GPS capture
|
2012-08-04 19:12:36 -03:00
|
|
|
#
|
2012-12-06 17:35:20 -04:00
|
|
|
#gps start
|
2012-08-04 19:12:36 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# startup is done; we don't want the shell because we
|
2012-12-06 17:35:20 -04:00
|
|
|
# use the same UART for telemetry
|
2012-08-04 19:12:36 -03:00
|
|
|
#
|
2012-12-06 17:35:20 -04:00
|
|
|
echo "[init] startup done"
|
2012-08-04 19:12:36 -03:00
|
|
|
exit
|