aboutsummaryrefslogblamecommitdiff
path: root/ROMFS/px4fmu_common/init.d/02_io_quad_x
blob: a37c26ad1d3e7217fdef9f7fb018dd8edd37f391 (plain) (tree)
1
2
3
4
5
6
7
8
9
10
     

                                                                






                                                      

              
                                  
                                     
  
 

                                          
                            



                    
               


                                    

 
                                     
 

                    
 
            
 
                                                     
 
 
                          
 

                  
 
                                       
 
                            
#!nsh

echo "[init] 02_io_quad_x: PX4FMU+PX4IO Quad X with PWM outputs"

#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
	# Set all params here, then disable autoconfig
	# TODO
	
	param set SYS_AUTOCONFIG 0
	param save /fs/microsd/params
fi

#
# Force some key parameters to sane values
# MAV_TYPE     2 = quadrotor
#
param set MAV_TYPE 2
 
#
# Start MAVLink
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000

#
# Start and configure PX4IO interface
#
sh /etc/init.d/rc.io

#
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix

#
# Set PWM output frequency
#
pwm -u 400 -m 0xff

#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor