2013-07-18 17:49:04 -03:00
|
|
|
#!nsh
|
|
|
|
#
|
|
|
|
# Flight startup script for PX4FMU+PX4IO
|
|
|
|
#
|
|
|
|
|
|
|
|
# disable USB and autostart
|
|
|
|
set USB no
|
|
|
|
set MODE custom
|
|
|
|
|
|
|
|
#
|
|
|
|
# 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
|
|
|
|
|
2013-08-02 10:47:04 -03:00
|
|
|
param set MC_ATTRATE_D 0.005
|
2013-07-18 17:49:04 -03:00
|
|
|
param set MC_ATTRATE_I 0.0
|
2013-08-02 10:47:04 -03:00
|
|
|
param set MC_ATTRATE_P 0.1
|
2013-07-18 17:49:04 -03:00
|
|
|
param set MC_ATT_D 0.0
|
|
|
|
param set MC_ATT_I 0.0
|
2013-08-02 10:47:04 -03:00
|
|
|
param set MC_ATT_P 4.5
|
2013-07-18 17:49:04 -03:00
|
|
|
param set MC_RCLOSS_THR 0.0
|
|
|
|
param set MC_YAWPOS_D 0.0
|
2013-08-02 10:47:04 -03:00
|
|
|
param set MC_YAWPOS_I 0.3
|
|
|
|
param set MC_YAWPOS_P 0.6
|
2013-07-18 17:49:04 -03:00
|
|
|
param set MC_YAWRATE_D 0.0
|
|
|
|
param set MC_YAWRATE_I 0.0
|
2013-08-02 10:47:04 -03:00
|
|
|
param set MC_YAWRATE_P 0.1
|
2013-07-18 17:49:04 -03:00
|
|
|
|
|
|
|
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 (depends on orb)
|
|
|
|
#
|
|
|
|
mavlink start
|
|
|
|
usleep 5000
|
2013-08-17 10:48:13 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# Start the commander (depends on orb, mavlink)
|
|
|
|
#
|
|
|
|
commander start
|
2013-07-18 17:49:04 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# Start PX4IO interface (depends on orb, commander)
|
|
|
|
#
|
|
|
|
px4io start
|
|
|
|
pwm -u 400 -m 0xff
|
|
|
|
|
|
|
|
#
|
|
|
|
# Allow PX4IO to recover from midair restarts.
|
|
|
|
# this is very unlikely, but quite safe and robust.
|
|
|
|
px4io recovery
|
|
|
|
|
|
|
|
#
|
|
|
|
# This sets a PWM right after startup (regardless of safety button)
|
|
|
|
#
|
|
|
|
px4io idle 900 900 900 900
|
|
|
|
|
|
|
|
#
|
|
|
|
# The values are for spinning motors when armed using DJI ESCs
|
|
|
|
#
|
|
|
|
px4io min 1200 1200 1200 1200
|
|
|
|
|
|
|
|
#
|
|
|
|
# Upper limits could be higher, this is on the safe side
|
|
|
|
#
|
|
|
|
px4io max 1800 1800 1800 1800
|
2013-08-11 11:54:00 -03:00
|
|
|
|
|
|
|
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
2013-07-18 17:49:04 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# 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)
|
|
|
|
#
|
|
|
|
attitude_estimator_ekf start
|
2013-08-11 11:54:00 -03:00
|
|
|
|
2013-07-18 17:49:04 -03:00
|
|
|
multirotor_att_control start
|
2013-08-11 12:39:10 -03:00
|
|
|
|
2013-07-18 17:49:04 -03:00
|
|
|
#
|
2013-08-11 12:39:10 -03:00
|
|
|
# Disable px4io topic limiting and start logging
|
2013-07-18 17:49:04 -03:00
|
|
|
#
|
2013-08-11 12:39:10 -03:00
|
|
|
if [ $BOARD == fmuv1 ]
|
2013-07-18 17:49:04 -03:00
|
|
|
then
|
2013-08-11 12:39:10 -03:00
|
|
|
px4io limit 200
|
|
|
|
sdlog2 start -r 50 -a -b 16
|
|
|
|
else
|
|
|
|
px4io limit 400
|
2013-08-11 13:42:20 -03:00
|
|
|
sdlog2 start -r 200 -a -b 16
|
2013-07-18 17:49:04 -03:00
|
|
|
fi
|