aboutsummaryrefslogblamecommitdiff
path: root/ROMFS/px4fmu_common/init.d/3031_io_phantom
blob: 0cf6ee39a54c7d528b235160b7f455d9866f9c07 (plain) (tree)
1
2
3
4
5
6
7
8
9
10
     
 
                                                             






                                                      



                                    


                              

                                  


                                 
                               

                          




                                   
                              
                                
                                   





                                    
                                  
                  
  


                                          
                             

                    
 
 
                                            
 



                                        
 





                                                          
 



                                        

 
                                                     
 







                                                                   

 
                             
 
                           
#!nsh

echo "[init] PX4FMU v1, v2 with or without IO on Phantom FPV"

#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
	# Set all params here, then disable autoconfig
	param set FW_AIRSPD_MIN 11.4
	param set FW_AIRSPD_TRIM 14
	param set FW_AIRSPD_MAX 22
	param set FW_L1_PERIOD 15
	param set FW_P_D 0
	param set FW_P_I 0
	param set FW_P_IMAX 15
	param set FW_P_LIM_MAX 45
	param set FW_P_LIM_MIN -45
	param set FW_P_P 60
	param set FW_P_RMAX_NEG 0
	param set FW_P_RMAX_POS 0
	param set FW_P_ROLLFF 2
	param set FW_R_D 0
	param set FW_R_I 5
	param set FW_R_IMAX 15
	param set FW_R_P 80
	param set FW_R_RMAX 60
	param set FW_THR_CRUISE 0.8
	param set FW_THR_LND_MAX 0
	param set FW_THR_MAX 1
	param set FW_THR_MIN 0.5
	param set FW_T_SINK_MAX 5.0
	param set FW_T_SINK_MIN 2.0
	param set FW_Y_ROLLFF 1.0
	param set RC_SCALE_ROLL 0.6
	param set RC_SCALE_PITCH 0.6
	param set TRIM_PITCH 0.1

	param set SYS_AUTOCONFIG 0
	param save
fi
 
#
# Force some key parameters to sane values
# MAV_TYPE     1 = fixed wing
#
param set MAV_TYPE 1

#
# Start and configure PX4IO or FMU interface
#
if px4io detect
then
	# Start MAVLink (depends on orb)
	mavlink start

	sh /etc/init.d/rc.io
	# Limit to 100 Hz updates and (implicit) 50 Hz PWM
	px4io limit 100
else
	# Start MAVLink (on UART1 / ttyS0)
	mavlink start -d /dev/ttyS0

	fmu mode_pwm
	param set BAT_V_SCALING 0.004593
	set EXIT_ON_END yes
fi

#
# Load mixer and start controllers (depends on px4io)
#
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
then
	echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
	mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
else
	echo "Using /etc/mixers/FMU_Q.mix"
	mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
fi

#
# Start common fixedwing apps
#
sh /etc/init.d/rc.fixedwing