You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
108 lines
1.9 KiB
108 lines
1.9 KiB
12 years ago
|
#!nsh
|
||
|
#
|
||
|
# Flight startup script for PX4FMU with PWM outputs.
|
||
|
#
|
||
|
|
||
12 years ago
|
# disable USB and autostart
|
||
12 years ago
|
set USB no
|
||
|
set MODE custom
|
||
|
|
||
|
echo "[init] doing PX4FMU Quad startup..."
|
||
|
|
||
|
#
|
||
|
# Start the ORB
|
||
|
#
|
||
|
uorb start
|
||
|
|
||
|
#
|
||
|
# Load microSD params
|
||
|
#
|
||
|
echo "[init] loading microSD params"
|
||
12 years ago
|
param select /fs/microsd/params
|
||
|
if [ -f /fs/microsd/params ]
|
||
12 years ago
|
then
|
||
12 years ago
|
param load /fs/microsd/params
|
||
12 years ago
|
fi
|
||
12 years ago
|
|
||
|
#
|
||
|
# Load default params for this platform
|
||
|
#
|
||
|
if param compare SYS_AUTOCONFIG 1
|
||
|
then
|
||
|
# Set all params here, then disable autoconfig
|
||
12 years ago
|
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
|
||
|
|
||
12 years ago
|
param set SYS_AUTOCONFIG 0
|
||
12 years ago
|
param save /fs/microsd/params
|
||
12 years ago
|
fi
|
||
|
|
||
12 years ago
|
#
|
||
|
# 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
|
||
12 years ago
|
|
||
|
#
|
||
|
# Start GPS interface (depends on orb)
|
||
|
#
|
||
|
gps start
|
||
12 years ago
|
|
||
|
#
|
||
|
# 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
|
||
12 years ago
|
pwm -u 400 -m 0xff
|
||
12 years ago
|
|
||
|
#
|
||
|
# Start attitude control
|
||
|
#
|
||
|
multirotor_att_control start
|
||
12 years ago
|
|
||
|
#
|
||
|
# Start logging
|
||
|
#
|
||
|
sdlog2 start -r 50 -a -b 14
|
||
12 years ago
|
|
||
12 years ago
|
#
|
||
|
# Start system state
|
||
|
#
|
||
|
if blinkm start
|
||
|
then
|
||
|
blinkm systemstate
|
||
|
fi
|