mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ROMFS: added new ROMFS for VR Brain 5.2 and VR Micro Brain 5.2
This commit is contained in:
parent
35c7a74256
commit
b278e058fa
252
mk/VRBRAIN/ROMFS_VRBRAIN52_APM/init.d/rc.APM
Normal file
252
mk/VRBRAIN/ROMFS_VRBRAIN52_APM/init.d/rc.APM
Normal file
@ -0,0 +1,252 @@
|
||||
#!nsh
|
||||
|
||||
# APM startup script for NuttX on VRBRAIN
|
||||
|
||||
# To disable APM startup add a /fs/microsd/APM/nostart file
|
||||
|
||||
# check for an old file called APM, caused by
|
||||
# a bug in an earlier firmware release
|
||||
if [ -f /fs/microsd/APM ]
|
||||
then
|
||||
echo "[APM] APM file found - renaming"
|
||||
mv /fs/microsd/APM /fs/microsd/APM.old
|
||||
fi
|
||||
|
||||
if [ -f /fs/microsd/APM/nostart ]
|
||||
then
|
||||
echo "[APM] APM/nostart found - skipping APM startup"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
# mount binfs so we can find the built-in apps
|
||||
if [ -f /bin/reboot ]
|
||||
then
|
||||
echo "[APM] binfs already mounted"
|
||||
else
|
||||
echo "[APM] Mounting binfs"
|
||||
if mount -t binfs /dev/null /bin
|
||||
then
|
||||
echo "[APM] binfs mounted OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
fi
|
||||
|
||||
if rm /fs/microsd/APM/boot.log
|
||||
then
|
||||
echo "[APM] Removed old boot.log"
|
||||
fi
|
||||
set logfile /fs/microsd/APM/BOOT.LOG
|
||||
|
||||
if [ ! -f /bin/ArduPilot ]
|
||||
then
|
||||
echo "[APM] /bin/ArduPilot not found"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
if mkdir /fs/microsd/APM > /dev/null
|
||||
then
|
||||
echo "[APM] Created APM directory"
|
||||
fi
|
||||
|
||||
echo "[APM] Starting UORB"
|
||||
if uorb start
|
||||
then
|
||||
echo "[APM] UORB started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting ADC"
|
||||
if adc start
|
||||
then
|
||||
echo "[APM] ADC started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting APM sensors"
|
||||
|
||||
echo "[APM] Starting MS5611 Internal"
|
||||
if ms5611 -I start
|
||||
then
|
||||
echo "[APM] MS5611 onboard started OK"
|
||||
else
|
||||
echo "[APM] MS5611 onboard start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MS5611 External EXP"
|
||||
if ms5611 -X start
|
||||
then
|
||||
echo "[APM] MS5611 external EXP started OK"
|
||||
else
|
||||
echo "[APM] MS5611 external EXP start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MS5611 External IMU"
|
||||
if ms5611 -U start
|
||||
then
|
||||
echo "[APM] MS5611 external IMU started OK"
|
||||
else
|
||||
echo "[APM] MS5611 external IMU start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting HMC5883 External GPS"
|
||||
if hmc5883 -X start
|
||||
then
|
||||
echo "[APM] HMC5883 External GPS started OK"
|
||||
if hmc5883 -X calibrate
|
||||
then
|
||||
echo "[APM] HMC5883 External GPS calibrate OK"
|
||||
else
|
||||
echo "[APM] HMC5883 External GPS calibrate failed"
|
||||
fi
|
||||
else
|
||||
echo "[APM] HMC5883 External GPS start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting HMC5883 Internal"
|
||||
if hmc5883 -I start
|
||||
then
|
||||
echo "[APM] HMC5883 Internal started OK"
|
||||
if hmc5883 -I calibrate
|
||||
then
|
||||
echo "[APM] HMC5883 Internal calibrate OK"
|
||||
else
|
||||
echo "[APM] HMC5883 Internal calibrate failed"
|
||||
fi
|
||||
else
|
||||
echo "[APM] HMC5883 Internal start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting HMC5983 External EXP"
|
||||
if hmc5983 -X start
|
||||
then
|
||||
echo "[APM] HMC5983 external EXP started OK"
|
||||
if hmc5983 -X calibrate
|
||||
then
|
||||
echo "[APM] HMC5983 external EXP calibrate OK"
|
||||
else
|
||||
echo "[APM] HMC5983 external EXP calibrate failed"
|
||||
fi
|
||||
else
|
||||
echo "[APM] HMC5983 external EXP start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting HMC5983 External IMU"
|
||||
if hmc5983 -U start
|
||||
then
|
||||
echo "[APM] HMC5983 external IMU started OK"
|
||||
if hmc5983 -U calibrate
|
||||
then
|
||||
echo "[APM] HMC5983 external IMU calibrate OK"
|
||||
else
|
||||
echo "[APM] HMC5983 external IMU calibrate failed"
|
||||
fi
|
||||
else
|
||||
echo "[APM] HMC5983 external IMU start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MPU6000 Internal"
|
||||
if mpu6000 -I start
|
||||
then
|
||||
echo "[APM] MPU6000 onboard started OK"
|
||||
else
|
||||
echo "[APM] MPU6000 onboard start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MPU6000 External EXP"
|
||||
if mpu6000 -X start
|
||||
then
|
||||
echo "[APM] MPU6000 external EXP started OK"
|
||||
else
|
||||
echo "[APM] MPU6000 external EXP start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MPU6000 External IMU"
|
||||
if mpu6000 -U start
|
||||
then
|
||||
echo "[APM] MPU6000 external IMU started OK"
|
||||
else
|
||||
echo "[APM] MPU6000 external IMU start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MEAS I2C Airspeed"
|
||||
if meas_airspeed start
|
||||
then
|
||||
echo "Found MEAS airspeed sensor"
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MB12XX Range Finder Sensor"
|
||||
if mb12xx start
|
||||
then
|
||||
echo "Found mb12xx sensor"
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MTD driver"
|
||||
if mtd start /fs/mtd
|
||||
then
|
||||
echo "[APM] MTD driver started OK"
|
||||
else
|
||||
echo "[APM] MTD driver start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] MTD driver read test"
|
||||
if mtd readtest /fs/mtd
|
||||
then
|
||||
echo "[APM] MTD driver readtest OK"
|
||||
else
|
||||
echo "[APM] MTD driver failed to read"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting VROUTPUT driver"
|
||||
vroutput mode_pwm
|
||||
#if vroutput mode_pwm
|
||||
#then
|
||||
# echo "[APM] VROUTPUT driver started OK"
|
||||
#else
|
||||
# echo "[APM] VROUTPUT driver start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
#fi
|
||||
|
||||
echo "[APM] Starting VRINPUT driver"
|
||||
vrinput start
|
||||
#if vrinput start
|
||||
#then
|
||||
# echo "[APM] VRINPUT driver started OK"
|
||||
#else
|
||||
# echo "[APM] VRINPUT driver start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
#fi
|
||||
|
||||
set sketch NONE
|
||||
set deviceA /dev/ttyACM0
|
||||
set deviceC /dev/ttyS2
|
||||
|
||||
echo "[APM] Starting ArduPilot"
|
||||
#if ArduPilot -d $deviceA -d2 $deviceC start
|
||||
if ArduPilot start
|
||||
then
|
||||
echo "[APM] ArduPilot started OK"
|
||||
else
|
||||
echo "[APM] ArduPilot start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Exiting from nsh shell"
|
||||
exit
|
||||
|
||||
echo "[APM] Script finished"
|
||||
|
225
mk/VRBRAIN/ROMFS_VRBRAIN52_APM/init.d/rc.APMNS
Normal file
225
mk/VRBRAIN/ROMFS_VRBRAIN52_APM/init.d/rc.APMNS
Normal file
@ -0,0 +1,225 @@
|
||||
#!nsh
|
||||
|
||||
# APM startup script for NuttX on VRBRAIN
|
||||
|
||||
# mount binfs so we can find the built-in apps
|
||||
if [ -f /bin/reboot ]
|
||||
then
|
||||
echo "[APMNS] binfs already mounted"
|
||||
else
|
||||
echo "[APMNS] Mounting binfs"
|
||||
if mount -t binfs /dev/null /bin
|
||||
then
|
||||
echo "[APMNS] binfs mounted OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ ! -f /bin/ArduPilot ]
|
||||
then
|
||||
echo "[APMNS] /bin/ArduPilot not found"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting UORB"
|
||||
if uorb start
|
||||
then
|
||||
echo "[APMNS] UORB started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting ADC"
|
||||
if adc start
|
||||
then
|
||||
echo "[APMNS] ADC started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting APM sensors"
|
||||
|
||||
echo "[APMNS] Starting MS5611 Internal"
|
||||
if ms5611 -I start
|
||||
then
|
||||
echo "[APMNS] MS5611 onboard started OK"
|
||||
else
|
||||
echo "[APMNS] MS5611 onboard start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MS5611 External EXP"
|
||||
if ms5611 -X start
|
||||
then
|
||||
echo "[APMNS] MS5611 external EXP started OK"
|
||||
else
|
||||
echo "[APMNS] MS5611 external EXP start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MS5611 External IMU"
|
||||
if ms5611 -U start
|
||||
then
|
||||
echo "[APMNS] MS5611 external IMU started OK"
|
||||
else
|
||||
echo "[APMNS] MS5611 external IMU start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting HMC5883 External GPS"
|
||||
if hmc5883 -X start
|
||||
then
|
||||
echo "[APMNS] HMC5883 External GPS started OK"
|
||||
if hmc5883 -X calibrate
|
||||
then
|
||||
echo "[APMNS] HMC5883 External GPS calibrate OK"
|
||||
else
|
||||
echo "[APMNS] HMC5883 External GPS calibrate failed"
|
||||
fi
|
||||
else
|
||||
echo "[APMNS] HMC5883 External GPS start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting HMC5883 Internal"
|
||||
if hmc5883 -I start
|
||||
then
|
||||
echo "[APMNS] HMC5883 Internal started OK"
|
||||
if hmc5883 -I calibrate
|
||||
then
|
||||
echo "[APMNS] HMC5883 Internal calibrate OK"
|
||||
else
|
||||
echo "[APMNS] HMC5883 Internal calibrate failed"
|
||||
fi
|
||||
else
|
||||
echo "[APMNS] HMC5883 Internal start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting HMC5983 External EXP"
|
||||
if hmc5983 -X start
|
||||
then
|
||||
echo "[APMNS] HMC5983 external EXP started OK"
|
||||
if hmc5983 -X calibrate
|
||||
then
|
||||
echo "[APMNS] HMC5983 external EXP calibrate OK"
|
||||
else
|
||||
echo "[APMNS] HMC5983 external EXP calibrate failed"
|
||||
fi
|
||||
else
|
||||
echo "[APMNS] HMC5983 external EXP start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting HMC5983 External IMU"
|
||||
if hmc5983 -U start
|
||||
then
|
||||
echo "[APMNS] HMC5983 external IMU started OK"
|
||||
if hmc5983 -U calibrate
|
||||
then
|
||||
echo "[APMNS] HMC5983 external IMU calibrate OK"
|
||||
else
|
||||
echo "[APMNS] HMC5983 external IMU calibrate failed"
|
||||
fi
|
||||
else
|
||||
echo "[APMNS] HMC5983 external IMU start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MPU6000 Internal"
|
||||
if mpu6000 -I start
|
||||
then
|
||||
echo "[APMNS] MPU6000 onboard started OK"
|
||||
else
|
||||
echo "[APMNS] MPU6000 onboard start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MPU6000 External EXP"
|
||||
if mpu6000 -X start
|
||||
then
|
||||
echo "[APMNS] MPU6000 external EXP started OK"
|
||||
else
|
||||
echo "[APMNS] MPU6000 external EXP start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MPU6000 External IMU"
|
||||
if mpu6000 -U start
|
||||
then
|
||||
echo "[APMNS] MPU6000 external IMU started OK"
|
||||
else
|
||||
echo "[APMNS] MPU6000 external IMU start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MEAS I2C Airspeed"
|
||||
if meas_airspeed start
|
||||
then
|
||||
echo "Found MEAS airspeed sensor"
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MB12XX Range Finder Sensor"
|
||||
if mb12xx start
|
||||
then
|
||||
echo "Found mb12xx sensor"
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MTD driver"
|
||||
if mtd start /fs/mtd
|
||||
then
|
||||
echo "[APMNS] MTD driver started OK"
|
||||
else
|
||||
echo "[APMNS] MTD driver start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] MTD driver read test"
|
||||
if mtd readtest /fs/mtd
|
||||
then
|
||||
echo "[APMNS] MTD driver readtest OK"
|
||||
else
|
||||
echo "[APMNS] MTD driver failed to read"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting VROUTPUT driver"
|
||||
vroutput mode_pwm
|
||||
#if vroutput mode_pwm
|
||||
#then
|
||||
# echo "[APMNS] VROUTPUT driver started OK"
|
||||
#else
|
||||
# echo "[APMNS] VROUTPUT driver start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
#fi
|
||||
|
||||
echo "[APMNS] Starting VRINPUT driver"
|
||||
vrinput start
|
||||
#if vrinput start
|
||||
#then
|
||||
# echo "[APMNS] VRINPUT driver started OK"
|
||||
#else
|
||||
# echo "[APMNS] VRINPUT driver start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
#fi
|
||||
|
||||
set sketch NONE
|
||||
set deviceA /dev/ttyACM0
|
||||
set deviceC /dev/ttyS2
|
||||
|
||||
echo "[APMNS] Starting ArduPilot"
|
||||
#if ArduPilot -d $deviceA -d2 $deviceC start
|
||||
if ArduPilot start
|
||||
then
|
||||
echo "[APMNS] ArduPilot started OK"
|
||||
else
|
||||
echo "[APMNS] ArduPilot start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Exiting from nsh shell"
|
||||
exit
|
||||
|
||||
echo "[APMNS] Script finished"
|
||||
|
7
mk/VRBRAIN/ROMFS_VRBRAIN52_APM/init.d/rc.error
Normal file
7
mk/VRBRAIN/ROMFS_VRBRAIN52_APM/init.d/rc.error
Normal file
@ -0,0 +1,7 @@
|
||||
echo "Error in startup"
|
||||
|
||||
nshterm /dev/ttyACM0 &
|
||||
sleep 1
|
||||
nshterm /dev/ttyS0 &
|
||||
sleep 1
|
||||
exit
|
100
mk/VRBRAIN/ROMFS_VRBRAIN52_APM/init.d/rcS
Normal file
100
mk/VRBRAIN/ROMFS_VRBRAIN52_APM/init.d/rcS
Normal file
@ -0,0 +1,100 @@
|
||||
#!nsh
|
||||
#
|
||||
# VRBRAIN startup script.
|
||||
#
|
||||
# This script is responsible for:
|
||||
#
|
||||
# - mounting the microSD card (if present)
|
||||
# - running the user startup script from the microSD card (if present)
|
||||
# - detecting the configuration of the system and picking a suitable
|
||||
# startup script to continue with
|
||||
#
|
||||
# Note: DO NOT add configuration-specific commands to this script;
|
||||
# add them to the per-configuration scripts instead.
|
||||
#
|
||||
|
||||
#
|
||||
# Default to auto-start mode. An init script on the microSD card
|
||||
# can change this to prevent automatic startup of the flight script.
|
||||
#
|
||||
set MODE autostart
|
||||
set USB autoconnect
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
echo "[init] looking for microSD..."
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[init] card mounted at /fs/microsd"
|
||||
set HAVE_MICROSD 1
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
set HAVE_MICROSD 0
|
||||
fi
|
||||
|
||||
#
|
||||
# Look for an init script on the microSD card.
|
||||
#
|
||||
# To prevent automatic startup in the current flight mode,
|
||||
# the script should set MODE to some other value.
|
||||
#
|
||||
if [ -f /fs/microsd/etc/rc ]
|
||||
then
|
||||
echo "[init] reading /fs/microsd/etc/rc"
|
||||
sh /fs/microsd/etc/rc
|
||||
fi
|
||||
# Also consider rc.txt files
|
||||
if [ -f /fs/microsd/etc/rc.txt ]
|
||||
then
|
||||
echo "[init] reading /fs/microsd/etc/rc.txt"
|
||||
sh /fs/microsd/etc/rc.txt
|
||||
fi
|
||||
|
||||
#
|
||||
# Check for USB host
|
||||
#
|
||||
if [ $USB != autoconnect ]
|
||||
then
|
||||
echo "[init] not connecting USB"
|
||||
else
|
||||
if sercon
|
||||
then
|
||||
echo "[init] USB interface connected"
|
||||
else
|
||||
echo "[init] No USB connected"
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $HAVE_MICROSD == 1 ]
|
||||
then
|
||||
if [ -f /fs/microsd/bootloader.bin ]
|
||||
then
|
||||
bl_update /fs/microsd/bootloader.bin
|
||||
rm /fs/microsd/bootloader.bin
|
||||
else
|
||||
fi
|
||||
|
||||
if [ ! -f /fs/microsd/APM/nostart ]
|
||||
then
|
||||
if [ -f /etc/init.d/rc.APM ]
|
||||
then
|
||||
echo "[init] Running rc.APM"
|
||||
# if APM startup is successful then nsh will exit
|
||||
sh /etc/init.d/rc.APM
|
||||
else
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
||||
else
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
||||
else
|
||||
if [ -f /etc/init.d/rc.APMNS ]
|
||||
then
|
||||
echo "[init] Running rc.APM without SD"
|
||||
# if APM startup is successful then nsh will exit
|
||||
sh /etc/init.d/rc.APMNS
|
||||
else
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
||||
fi
|
171
mk/VRBRAIN/ROMFS_VRUBRAIN52_APM/init.d/rc.APM
Normal file
171
mk/VRBRAIN/ROMFS_VRUBRAIN52_APM/init.d/rc.APM
Normal file
@ -0,0 +1,171 @@
|
||||
#!nsh
|
||||
|
||||
# APM startup script for NuttX on VRBRAIN
|
||||
|
||||
# To disable APM startup add a /fs/microsd/APM/nostart file
|
||||
|
||||
# check for an old file called APM, caused by
|
||||
# a bug in an earlier firmware release
|
||||
if [ -f /fs/microsd/APM ]
|
||||
then
|
||||
echo "[APM] APM file found - renaming"
|
||||
mv /fs/microsd/APM /fs/microsd/APM.old
|
||||
fi
|
||||
|
||||
if [ -f /fs/microsd/APM/nostart ]
|
||||
then
|
||||
echo "[APM] APM/nostart found - skipping APM startup"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
# mount binfs so we can find the built-in apps
|
||||
if [ -f /bin/reboot ]
|
||||
then
|
||||
echo "[APM] binfs already mounted"
|
||||
else
|
||||
echo "[APM] Mounting binfs"
|
||||
if mount -t binfs /dev/null /bin
|
||||
then
|
||||
echo "[APM] binfs mounted OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
fi
|
||||
|
||||
if rm /fs/microsd/APM/boot.log
|
||||
then
|
||||
echo "[APM] Removed old boot.log"
|
||||
fi
|
||||
set logfile /fs/microsd/APM/BOOT.LOG
|
||||
|
||||
if [ ! -f /bin/ArduPilot ]
|
||||
then
|
||||
echo "[APM] /bin/ArduPilot not found"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
if mkdir /fs/microsd/APM > /dev/null
|
||||
then
|
||||
echo "[APM] Created APM directory"
|
||||
fi
|
||||
|
||||
echo "[APM] Starting UORB"
|
||||
if uorb start
|
||||
then
|
||||
echo "[APM] UORB started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting ADC"
|
||||
if adc start
|
||||
then
|
||||
echo "[APM] ADC started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting APM sensors"
|
||||
|
||||
echo "[APM] Starting MS5611 Internal"
|
||||
if ms5611 -I start
|
||||
then
|
||||
echo "[APM] MS5611 onboard started OK"
|
||||
else
|
||||
echo "[APM] MS5611 onboard start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting HMC5883 External GPS"
|
||||
if hmc5883 -X start
|
||||
then
|
||||
echo "[APM] HMC5883 External GPS started OK"
|
||||
if hmc5883 -X calibrate
|
||||
then
|
||||
echo "[APM] HMC5883 External GPS calibrate OK"
|
||||
else
|
||||
echo "[APM] HMC5883 External GPS calibrate failed"
|
||||
fi
|
||||
else
|
||||
echo "[APM] HMC5883 External GPS start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MPU6000 Internal"
|
||||
if mpu6000 -I start
|
||||
then
|
||||
echo "[APM] MPU6000 onboard started OK"
|
||||
else
|
||||
echo "[APM] MPU6000 onboard start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MEAS I2C Airspeed"
|
||||
if meas_airspeed start
|
||||
then
|
||||
echo "Found MEAS airspeed sensor"
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MB12XX Range Finder Sensor"
|
||||
if mb12xx start
|
||||
then
|
||||
echo "Found mb12xx sensor"
|
||||
fi
|
||||
|
||||
echo "[APM] Starting MTD driver"
|
||||
if mtd start /fs/mtd
|
||||
then
|
||||
echo "[APM] MTD driver started OK"
|
||||
else
|
||||
echo "[APM] MTD driver start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] MTD driver read test"
|
||||
if mtd readtest /fs/mtd
|
||||
then
|
||||
echo "[APM] MTD driver readtest OK"
|
||||
else
|
||||
echo "[APM] MTD driver failed to read"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Starting VROUTPUT driver"
|
||||
vroutput mode_pwm
|
||||
#if vroutput mode_pwm
|
||||
#then
|
||||
# echo "[APM] VROUTPUT driver started OK"
|
||||
#else
|
||||
# echo "[APM] VROUTPUT driver start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
#fi
|
||||
|
||||
echo "[APM] Starting VRINPUT driver"
|
||||
vrinput start
|
||||
#if vrinput start
|
||||
#then
|
||||
# echo "[APM] VRINPUT driver started OK"
|
||||
#else
|
||||
# echo "[APM] VRINPUT driver start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
#fi
|
||||
|
||||
set sketch NONE
|
||||
set deviceA /dev/ttyACM0
|
||||
set deviceC /dev/ttyS2
|
||||
|
||||
echo "[APM] Starting ArduPilot"
|
||||
#if ArduPilot -d $deviceA -d2 $deviceC start
|
||||
if ArduPilot start
|
||||
then
|
||||
echo "[APM] ArduPilot started OK"
|
||||
else
|
||||
echo "[APM] ArduPilot start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APM] Exiting from nsh shell"
|
||||
exit
|
||||
|
||||
echo "[APM] Script finished"
|
||||
|
144
mk/VRBRAIN/ROMFS_VRUBRAIN52_APM/init.d/rc.APMNS
Normal file
144
mk/VRBRAIN/ROMFS_VRUBRAIN52_APM/init.d/rc.APMNS
Normal file
@ -0,0 +1,144 @@
|
||||
#!nsh
|
||||
|
||||
# APM startup script for NuttX on VRBRAIN
|
||||
|
||||
# mount binfs so we can find the built-in apps
|
||||
if [ -f /bin/reboot ]
|
||||
then
|
||||
echo "[APMNS] binfs already mounted"
|
||||
else
|
||||
echo "[APMNS] Mounting binfs"
|
||||
if mount -t binfs /dev/null /bin
|
||||
then
|
||||
echo "[APMNS] binfs mounted OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ ! -f /bin/ArduPilot ]
|
||||
then
|
||||
echo "[APMNS] /bin/ArduPilot not found"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting UORB"
|
||||
if uorb start
|
||||
then
|
||||
echo "[APMNS] UORB started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting ADC"
|
||||
if adc start
|
||||
then
|
||||
echo "[APMNS] ADC started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting APM sensors"
|
||||
|
||||
echo "[APMNS] Starting MS5611 Internal"
|
||||
if ms5611 -I start
|
||||
then
|
||||
echo "[APMNS] MS5611 onboard started OK"
|
||||
else
|
||||
echo "[APMNS] MS5611 onboard start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting HMC5883 External GPS"
|
||||
if hmc5883 -X start
|
||||
then
|
||||
echo "[APMNS] HMC5883 External GPS started OK"
|
||||
if hmc5883 -X calibrate
|
||||
then
|
||||
echo "[APMNS] HMC5883 External GPS calibrate OK"
|
||||
else
|
||||
echo "[APMNS] HMC5883 External GPS calibrate failed"
|
||||
fi
|
||||
else
|
||||
echo "[APMNS] HMC5883 External GPS start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MPU6000 Internal"
|
||||
if mpu6000 -I start
|
||||
then
|
||||
echo "[APMNS] MPU6000 onboard started OK"
|
||||
else
|
||||
echo "[APMNS] MPU6000 onboard start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MEAS I2C Airspeed"
|
||||
if meas_airspeed start
|
||||
then
|
||||
echo "Found MEAS airspeed sensor"
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MB12XX Range Finder Sensor"
|
||||
if mb12xx start
|
||||
then
|
||||
echo "Found mb12xx sensor"
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting MTD driver"
|
||||
if mtd start /fs/mtd
|
||||
then
|
||||
echo "[APMNS] MTD driver started OK"
|
||||
else
|
||||
echo "[APMNS] MTD driver start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] MTD driver read test"
|
||||
if mtd readtest /fs/mtd
|
||||
then
|
||||
echo "[APMNS] MTD driver readtest OK"
|
||||
else
|
||||
echo "[APMNS] MTD driver failed to read"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Starting VROUTPUT driver"
|
||||
vroutput mode_pwm
|
||||
#if vroutput mode_pwm
|
||||
#then
|
||||
# echo "[APMNS] VROUTPUT driver started OK"
|
||||
#else
|
||||
# echo "[APMNS] VROUTPUT driver start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
#fi
|
||||
|
||||
echo "[APMNS] Starting VRINPUT driver"
|
||||
vrinput start
|
||||
#if vrinput start
|
||||
#then
|
||||
# echo "[APMNS] VRINPUT driver started OK"
|
||||
#else
|
||||
# echo "[APMNS] VRINPUT driver start failed"
|
||||
# sh /etc/init.d/rc.error
|
||||
#fi
|
||||
|
||||
set sketch NONE
|
||||
set deviceA /dev/ttyACM0
|
||||
set deviceC /dev/ttyS2
|
||||
|
||||
echo "[APMNS] Starting ArduPilot"
|
||||
#if ArduPilot -d $deviceA -d2 $deviceC start
|
||||
if ArduPilot start
|
||||
then
|
||||
echo "[APMNS] ArduPilot started OK"
|
||||
else
|
||||
echo "[APMNS] ArduPilot start failed"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
echo "[APMNS] Exiting from nsh shell"
|
||||
exit
|
||||
|
||||
echo "[APMNS] Script finished"
|
||||
|
7
mk/VRBRAIN/ROMFS_VRUBRAIN52_APM/init.d/rc.error
Normal file
7
mk/VRBRAIN/ROMFS_VRUBRAIN52_APM/init.d/rc.error
Normal file
@ -0,0 +1,7 @@
|
||||
echo "Error in startup"
|
||||
|
||||
nshterm /dev/ttyACM0 &
|
||||
sleep 1
|
||||
nshterm /dev/ttyS0 &
|
||||
sleep 1
|
||||
exit
|
100
mk/VRBRAIN/ROMFS_VRUBRAIN52_APM/init.d/rcS
Normal file
100
mk/VRBRAIN/ROMFS_VRUBRAIN52_APM/init.d/rcS
Normal file
@ -0,0 +1,100 @@
|
||||
#!nsh
|
||||
#
|
||||
# VRBRAIN startup script.
|
||||
#
|
||||
# This script is responsible for:
|
||||
#
|
||||
# - mounting the microSD card (if present)
|
||||
# - running the user startup script from the microSD card (if present)
|
||||
# - detecting the configuration of the system and picking a suitable
|
||||
# startup script to continue with
|
||||
#
|
||||
# Note: DO NOT add configuration-specific commands to this script;
|
||||
# add them to the per-configuration scripts instead.
|
||||
#
|
||||
|
||||
#
|
||||
# Default to auto-start mode. An init script on the microSD card
|
||||
# can change this to prevent automatic startup of the flight script.
|
||||
#
|
||||
set MODE autostart
|
||||
set USB autoconnect
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
echo "[init] looking for microSD..."
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[init] card mounted at /fs/microsd"
|
||||
set HAVE_MICROSD 1
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
set HAVE_MICROSD 0
|
||||
fi
|
||||
|
||||
#
|
||||
# Look for an init script on the microSD card.
|
||||
#
|
||||
# To prevent automatic startup in the current flight mode,
|
||||
# the script should set MODE to some other value.
|
||||
#
|
||||
if [ -f /fs/microsd/etc/rc ]
|
||||
then
|
||||
echo "[init] reading /fs/microsd/etc/rc"
|
||||
sh /fs/microsd/etc/rc
|
||||
fi
|
||||
# Also consider rc.txt files
|
||||
if [ -f /fs/microsd/etc/rc.txt ]
|
||||
then
|
||||
echo "[init] reading /fs/microsd/etc/rc.txt"
|
||||
sh /fs/microsd/etc/rc.txt
|
||||
fi
|
||||
|
||||
#
|
||||
# Check for USB host
|
||||
#
|
||||
if [ $USB != autoconnect ]
|
||||
then
|
||||
echo "[init] not connecting USB"
|
||||
else
|
||||
if sercon
|
||||
then
|
||||
echo "[init] USB interface connected"
|
||||
else
|
||||
echo "[init] No USB connected"
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $HAVE_MICROSD == 1 ]
|
||||
then
|
||||
if [ -f /fs/microsd/bootloader.bin ]
|
||||
then
|
||||
bl_update /fs/microsd/bootloader.bin
|
||||
rm /fs/microsd/bootloader.bin
|
||||
else
|
||||
fi
|
||||
|
||||
if [ ! -f /fs/microsd/APM/nostart ]
|
||||
then
|
||||
if [ -f /etc/init.d/rc.APM ]
|
||||
then
|
||||
echo "[init] Running rc.APM"
|
||||
# if APM startup is successful then nsh will exit
|
||||
sh /etc/init.d/rc.APM
|
||||
else
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
||||
else
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
||||
else
|
||||
if [ -f /etc/init.d/rc.APMNS ]
|
||||
then
|
||||
echo "[init] Running rc.APM without SD"
|
||||
# if APM startup is successful then nsh will exit
|
||||
sh /etc/init.d/rc.APMNS
|
||||
else
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
||||
fi
|
Loading…
Reference in New Issue
Block a user