forked from Archive/PX4-Autopilot
autostart for multicopters: frame-specific default parameters reverted and cleaned up
This commit is contained in:
parent
6f506874eb
commit
16908f9aff
|
@ -2,11 +2,28 @@
|
|||
#
|
||||
# Team Blacksheep Discovery Quadcopter
|
||||
#
|
||||
# Simon Wilks <sjwilks@gmail.com>
|
||||
# Anton Babushkin <anton.babushkin@me.com>, Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# TODO review MC_YAWRATE_I
|
||||
param set MC_ROLL_P 8.0
|
||||
param set MC_ROLLRATE_P 0.07
|
||||
param set MC_ROLLRATE_I 0.05
|
||||
param set MC_ROLLRATE_D 0.0017
|
||||
param set MC_PITCH_P 8.0
|
||||
param set MC_PITCHRATE_P 0.14
|
||||
param set MC_PITCHRATE_I 0.1
|
||||
param set MC_PITCHRATE_D 0.0025
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.28
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
set MIXER FMU_quad_w
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_OUTPUTS 1234
|
||||
|
|
|
@ -9,9 +9,20 @@ sh /etc/init.d/rc.mc_defaults
|
|||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
# TODO tune roll/pitch separately
|
||||
param set MC_ROLL_P 9.0
|
||||
param set MC_ROLLRATE_P 0.13
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.004
|
||||
param set MC_PITCH_P 9.0
|
||||
param set MC_PITCHRATE_P 0.13
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.004
|
||||
param set MC_YAW_P 0.5
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
|
||||
param set BAT_V_SCALING 0.00989
|
||||
param set BAT_C_SCALING 0.0124
|
||||
fi
|
||||
|
|
|
@ -7,33 +7,9 @@
|
|||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER hexa_cox
|
||||
|
||||
# We only can run one channel group with one rate, so set all 8 channels
|
||||
set PWM_OUTPUTS 12345678
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
||||
|
|
|
@ -5,33 +5,8 @@
|
|||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_octo_cox
|
||||
set MIXER octo_cox
|
||||
|
||||
set PWM_OUTPUTS 12345678
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
||||
|
|
|
@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
|
|||
|
||||
set MIXER FMU_quad_x
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_OUTPUTS 1234
|
||||
|
|
|
@ -7,4 +7,21 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
set PWM_MIN 1175
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
set PWM_MIN 1175
|
||||
set PWM_MAX 1900
|
||||
|
|
|
@ -7,4 +7,22 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
set PWM_MIN 1175
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# TODO REVIEW
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
set PWM_MIN 1175
|
||||
set PWM_MAX 1900
|
||||
|
|
|
@ -1,8 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# HobbyKing X550 Quadcopter
|
||||
#
|
||||
# Todd Stellanova <tstellanova@gmail.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/4001_quad_x
|
|
@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
|
|||
|
||||
set MIXER FMU_quad_+
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_OUTPUTS 1234
|
||||
|
|
|
@ -9,6 +9,5 @@ sh /etc/init.d/rc.mc_defaults
|
|||
|
||||
set MIXER FMU_hexa_x
|
||||
|
||||
# We only can run one channel group with one rate,
|
||||
# so all 8 at 400 Hz
|
||||
set PWM_OUTPUTS 12345678
|
||||
# We only can run one channel group with one rate, so set all 8 channels
|
||||
set PWM_OUTPUTS 12345678
|
||||
|
|
|
@ -9,6 +9,5 @@ sh /etc/init.d/rc.mc_defaults
|
|||
|
||||
set MIXER FMU_hexa_+
|
||||
|
||||
# We only can run one channel group with one rate,
|
||||
# so all 8 at 400 Hz
|
||||
set PWM_OUTPUTS 12345678
|
||||
# We only can run one channel group with one rate, so set all 8 channels
|
||||
set PWM_OUTPUTS 12345678
|
||||
|
|
|
@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
|
|||
|
||||
set MIXER FMU_octo_x
|
||||
|
||||
set PWM_OUTPUTS 12345678
|
||||
set PWM_OUTPUTS 12345678
|
||||
|
|
|
@ -116,11 +116,6 @@ then
|
|||
sh /etc/init.d/4011_dji_f450
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4012 12
|
||||
then
|
||||
sh /etc/init.d/4012_hk_x550
|
||||
fi
|
||||
|
||||
#
|
||||
# Quad +
|
||||
#
|
||||
|
|
|
@ -4,22 +4,20 @@ set VEHICLE_TYPE mc
|
|||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for MC
|
||||
#
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.12
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.004
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.12
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.004
|
||||
param set MC_YAW_P 2.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAW_FF 0.5
|
||||
|
||||
param set MPC_THR_MAX 1.0
|
||||
param set MPC_THR_MIN 0.1
|
||||
param set MPC_XY_P 1.0
|
||||
|
@ -42,4 +40,4 @@ fi
|
|||
set PWM_RATE 400
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1075
|
||||
set PWM_MAX 2000
|
||||
set PWM_MAX 2000
|
||||
|
|
Loading…
Reference in New Issue