2013-09-13 16:05:41 -03:00
|
|
|
#!nsh
|
|
|
|
|
|
|
|
#
|
|
|
|
# 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
|
|
|
|
|
|
|
|
param set MC_ATTRATE_D 0.002
|
|
|
|
param set MC_ATTRATE_I 0.0
|
|
|
|
param set MC_ATTRATE_P 0.09
|
|
|
|
param set MC_ATT_D 0.0
|
|
|
|
param set MC_ATT_I 0.0
|
|
|
|
param set MC_ATT_P 6.8
|
|
|
|
param set MC_YAWPOS_D 0.0
|
|
|
|
param set MC_YAWPOS_I 0.0
|
|
|
|
param set MC_YAWPOS_P 2.0
|
|
|
|
param set MC_YAWRATE_D 0.005
|
|
|
|
param set MC_YAWRATE_I 0.2
|
|
|
|
param set MC_YAWRATE_P 0.3
|
|
|
|
param set NAV_TAKEOFF_ALT 3.0
|
|
|
|
param set MPC_TILT_MAX 0.5
|
|
|
|
param set MPC_THR_MAX 0.7
|
|
|
|
param set MPC_THR_MIN 0.3
|
|
|
|
param set MPC_XY_D 0
|
|
|
|
param set MPC_XY_P 0.5
|
|
|
|
param set MPC_XY_VEL_D 0
|
|
|
|
param set MPC_XY_VEL_I 0
|
|
|
|
param set MPC_XY_VEL_MAX 3
|
|
|
|
param set MPC_XY_VEL_P 0.2
|
|
|
|
param set MPC_Z_D 0
|
|
|
|
param set MPC_Z_P 1
|
|
|
|
param set MPC_Z_VEL_D 0
|
|
|
|
param set MPC_Z_VEL_I 0.1
|
|
|
|
param set MPC_Z_VEL_MAX 2
|
|
|
|
param set MPC_Z_VEL_P 0.20
|
|
|
|
|
|
|
|
param save
|
|
|
|
fi
|
|
|
|
|
|
|
|
#
|
|
|
|
# Force some key parameters to sane values
|
|
|
|
# MAV_TYPE 2 = quadrotor
|
|
|
|
#
|
|
|
|
param set MAV_TYPE 2
|
|
|
|
|
|
|
|
set EXIT_ON_END no
|
|
|
|
|
|
|
|
#
|
|
|
|
# Start the Mikrokopter ESC driver
|
|
|
|
#
|
|
|
|
if [ $MKBLCTRL_MODE == yes ]
|
|
|
|
then
|
|
|
|
if [ $MKBLCTRL_FRAME == x ]
|
|
|
|
then
|
|
|
|
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing"
|
|
|
|
mkblctrl -mkmode x
|
|
|
|
else
|
|
|
|
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing"
|
|
|
|
mkblctrl -mkmode +
|
|
|
|
fi
|
|
|
|
else
|
|
|
|
if [ $MKBLCTRL_FRAME == x ]
|
|
|
|
then
|
|
|
|
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame"
|
|
|
|
else
|
|
|
|
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame"
|
|
|
|
fi
|
|
|
|
mkblctrl
|
|
|
|
fi
|
|
|
|
|
|
|
|
usleep 10000
|
|
|
|
|
|
|
|
#
|
|
|
|
# Start and configure PX4IO or FMU interface
|
|
|
|
#
|
|
|
|
if px4io detect
|
|
|
|
then
|
|
|
|
# Start MAVLink (depends on orb)
|
|
|
|
mavlink start
|
|
|
|
usleep 5000
|
|
|
|
|
|
|
|
sh /etc/init.d/rc.io
|
|
|
|
else
|
|
|
|
fmu mode_pwm
|
|
|
|
# Start MAVLink (on UART1 / ttyS0)
|
|
|
|
mavlink start -d /dev/ttyS0
|
|
|
|
usleep 5000
|
|
|
|
param set BAT_V_SCALING 0.004593
|
|
|
|
set EXIT_ON_END yes
|
|
|
|
fi
|
|
|
|
|
|
|
|
#
|
|
|
|
# Load mixer
|
|
|
|
#
|
|
|
|
if [ $MKBLCTRL_FRAME == x ]
|
|
|
|
then
|
|
|
|
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
|
|
|
else
|
|
|
|
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
|
|
|
|
fi
|
|
|
|
|
|
|
|
#
|
2013-10-07 11:34:07 -03:00
|
|
|
# Set disarmed, min and max PWM signals
|
2013-09-13 16:05:41 -03:00
|
|
|
#
|
2013-10-07 11:34:07 -03:00
|
|
|
pwm disarmed -c 1234 -p 900
|
|
|
|
pwm min -c 1234 -p 1200
|
|
|
|
pwm max -c 1234 -p 1800
|
2013-09-13 16:05:41 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# Start common for all multirotors apps
|
|
|
|
#
|
|
|
|
sh /etc/init.d/rc.multirotor
|
|
|
|
|
|
|
|
if [ $EXIT_ON_END == yes ]
|
|
|
|
then
|
|
|
|
exit
|
|
|
|
fi
|