px4-firmware/ROMFS/px4fmu_common/init.d/40_io_segway

57 lines
823 B
Plaintext
Raw Normal View History

2013-07-28 23:28:04 -03:00
#!nsh
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
2013-08-25 14:27:11 -03:00
# TODO
2013-07-28 23:28:04 -03:00
param set SYS_AUTOCONFIG 0
param save
2013-07-28 23:28:04 -03:00
fi
#
# Force some key parameters to sane values
2013-08-25 14:27:11 -03:00
# MAV_TYPE 10 = ground rover
2013-07-28 23:28:04 -03:00
#
param set MAV_TYPE 10
2013-08-25 14:27:11 -03:00
2013-07-28 23:28:04 -03:00
#
# Start MAVLink (depends on orb)
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
2013-08-25 14:27:11 -03:00
# Start and configure PX4IO interface
2013-07-28 23:28:04 -03:00
#
2013-08-25 14:27:11 -03:00
sh /etc/init.d/rc.io
2013-07-28 23:28:04 -03:00
#
2013-08-25 14:27:11 -03:00
# Start the commander (depends on orb, mavlink)
2013-07-28 23:28:04 -03:00
#
2013-08-25 14:27:11 -03:00
commander start
2013-07-28 23:28:04 -03:00
#
# 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)
#
md25 start 3 0x58
segway start