mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
PX4: re-order startup to start mtd before ms5611
this avoids a bus locking issue on Pixracer
This commit is contained in:
parent
eb6848b8c2
commit
d47d3492e1
@ -211,6 +211,41 @@ else
|
|||||||
fi
|
fi
|
||||||
|
|
||||||
|
|
||||||
|
if mtd start /fs/mtd
|
||||||
|
then
|
||||||
|
echo "started mtd driver OK"
|
||||||
|
else
|
||||||
|
echo "failed to start mtd driver"
|
||||||
|
echo "failed to start mtd driver" >> $logfile
|
||||||
|
sh /etc/init.d/rc.error
|
||||||
|
fi
|
||||||
|
|
||||||
|
if mtd readtest /fs/mtd
|
||||||
|
then
|
||||||
|
echo "mtd readtest OK"
|
||||||
|
else
|
||||||
|
echo "failed to read mtd"
|
||||||
|
echo "failed to read mtd" >> $logfile
|
||||||
|
sh /etc/init.d/rc.error
|
||||||
|
fi
|
||||||
|
|
||||||
|
if [ $BOARD == FMUv2 -o $BOARD == FMUv4 ]
|
||||||
|
then
|
||||||
|
# the ramtron on FMUv2 is very fast and can handle trillions of
|
||||||
|
# writes. This full rw test on each boot ensures it is working
|
||||||
|
# properly. We have one board that failed this, so
|
||||||
|
# the test is arguably worth having
|
||||||
|
if mtd rwtest /fs/mtd
|
||||||
|
then
|
||||||
|
echo "mtd rwtest OK"
|
||||||
|
else
|
||||||
|
echo "failed to test mtd"
|
||||||
|
echo "failed to test mtd" >> $logfile
|
||||||
|
sh /etc/init.d/rc.error
|
||||||
|
fi
|
||||||
|
fi
|
||||||
|
|
||||||
|
|
||||||
echo "Starting APM sensors"
|
echo "Starting APM sensors"
|
||||||
|
|
||||||
if ms5611 start
|
if ms5611 start
|
||||||
@ -435,24 +470,6 @@ then
|
|||||||
echo "started pwm_input driver"
|
echo "started pwm_input driver"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if mtd start /fs/mtd
|
|
||||||
then
|
|
||||||
echo "started mtd driver OK"
|
|
||||||
else
|
|
||||||
echo "failed to start mtd driver"
|
|
||||||
echo "failed to start mtd driver" >> $logfile
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
|
|
||||||
if mtd readtest /fs/mtd
|
|
||||||
then
|
|
||||||
echo "mtd readtest OK"
|
|
||||||
else
|
|
||||||
echo "failed to read mtd"
|
|
||||||
echo "failed to read mtd" >> $logfile
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
|
|
||||||
# optional oreo leds
|
# optional oreo leds
|
||||||
if [ -f /bin/oreoled ]
|
if [ -f /bin/oreoled ]
|
||||||
then
|
then
|
||||||
@ -474,22 +491,6 @@ then
|
|||||||
echo "irlock started"
|
echo "irlock started"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $BOARD == FMUv2 -o $BOARD == FMUv4 ]
|
|
||||||
then
|
|
||||||
# the ramtron on FMUv2 is very fast and can handle trillions of
|
|
||||||
# writes. This full rw test on each boot ensures it is working
|
|
||||||
# properly. We have one board that failed this, so
|
|
||||||
# the test is arguably worth having
|
|
||||||
if mtd rwtest /fs/mtd
|
|
||||||
then
|
|
||||||
echo "mtd rwtest OK"
|
|
||||||
else
|
|
||||||
echo "failed to test mtd"
|
|
||||||
echo "failed to test mtd" >> $logfile
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
fi
|
|
||||||
|
|
||||||
echo Starting ArduPilot $deviceA $deviceC $deviceD
|
echo Starting ArduPilot $deviceA $deviceC $deviceD
|
||||||
if ArduPilot -d $deviceA -d2 $deviceC -d3 $deviceD start
|
if ArduPilot -d $deviceA -d2 $deviceC -d3 $deviceD start
|
||||||
then
|
then
|
||||||
|
Loading…
Reference in New Issue
Block a user