aboutsummaryrefslogblamecommitdiff
path: root/ROMFS/px4fmu_common/init.d/30_io_camflyer
blob: 5090b98a426224045535851a2a27853d512bd083 (plain) (tree)
1
2
3
4
5
6
7
8
9
10
     


                                        
 
                           
          
               

 
                                    






                                    

                               
    
                                     
  







                                                      
                                     
  








                                                            
                                                                   
 

















                                                                                                      

 
                                




                                    
                                               



               
                                                   
 
           
 
 


                                                   



                                                 

 
                                           
 
                         

 
                                      
 





                                               

 
                                                     






                                                
                           
 




                    
                          
  
#!nsh
#
# Flight startup script for PX4FMU+PX4IO
#
 
# disable USB and autostart
set USB no
set MODE custom
 
#
# Start the ORB (first app to start)
#
uorb start
 
#
# 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

#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
	# Set all params here, then disable autoconfig
	param set SYS_AUTOCONFIG 0
	param save /fs/microsd/params
fi
 
#
# Force some key parameters to sane values
# MAV_TYPE     1 = fixed wing, 2 = quadrotor, 13 = hexarotor
#              see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 1
 
#
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
#
if [ -f /fs/microsd/px4io.bin ]
then
	echo "PX4IO Firmware found. Checking Upgrade.."
	if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
	then
		echo "No newer version, skipping upgrade."
	else
		echo "Loading /fs/microsd/px4io.bin"
		if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
		then
			cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
			echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
		else
			echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
			echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
		fi
	fi
fi
 
#
# Start MAVLink (depends on orb)
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
 
#
# Start the commander (depends on orb, mavlink)
#
commander start
 
#
# Start PX4IO interface (depends on orb, commander)
#
px4io start
 
#
# Allow PX4IO to recover from midair restarts.
# this is very unlikely, but quite safe and robust.
px4io recovery

#
# Set actuator limit to 100 Hz update (50 Hz PWM)
px4io limit 100
 
#
# 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)
#
kalman_demo start
 
#
# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start
 
#
# Start logging
#
sdlog2 start -r 50 -a -b 14
 
#
# Start system state
#
if blinkm start
then
	blinkm systemstate
fi