forked from Archive/PX4-Autopilot
add placeholder autoconfig file for X550
This commit is contained in:
parent
3005c8aae0
commit
64f402ce83
|
@ -0,0 +1,107 @@
|
|||
#!nsh
|
||||
#
|
||||
# Flight startup script for PX4FMU with PWM outputs.
|
||||
#
|
||||
|
||||
# disable USB and autostart
|
||||
set USB no
|
||||
set MODE custom
|
||||
|
||||
echo "[init] doing PX4FMU Quad startup 666_fmu_quad_X550..."
|
||||
|
||||
#
|
||||
# Start the ORB
|
||||
#
|
||||
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 MC_ATTRATE_P 0.14
|
||||
param set MC_ATTRATE_I 0
|
||||
param set MC_ATTRATE_D 0.006
|
||||
param set MC_ATT_P 5.5
|
||||
param set MC_ATT_I 0
|
||||
param set MC_ATT_D 0
|
||||
param set MC_YAWPOS_D 0
|
||||
param set MC_YAWPOS_I 0
|
||||
param set MC_YAWPOS_P 0.6
|
||||
param set MC_YAWRATE_D 0
|
||||
param set MC_YAWRATE_I 0
|
||||
param set MC_YAWRATE_P 0.08
|
||||
param set RC_SCALE_PITCH 1
|
||||
param set RC_SCALE_ROLL 1
|
||||
param set RC_SCALE_YAW 3
|
||||
|
||||
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 2
|
||||
|
||||
#
|
||||
# Start MAVLink
|
||||
#
|
||||
mavlink start -d /dev/ttyS0 -b 57600
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start the sensors and test them.
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start the commander.
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator
|
||||
#
|
||||
attitude_estimator_ekf start
|
||||
|
||||
echo "[init] starting PWM output"
|
||||
fmu mode_pwm
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
pwm -u 400 -m 0xff
|
||||
|
||||
#
|
||||
# Start attitude control
|
||||
#
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
blinkm systemstate
|
||||
fi
|
Loading…
Reference in New Issue