15 changed files with 386 additions and 267 deletions
@ -0,0 +1,37 @@ |
|||||||
|
#!nsh |
||||||
|
# |
||||||
|
# Generic 10” Octo coaxial geometry |
||||||
|
# |
||||||
|
# Maintainers: 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 |
||||||
|
|
||||||
|
set VEHICLE_TYPE mc |
||||||
|
set MIXER FMU_octo_cox |
||||||
|
|
||||||
|
set PWM_OUTPUTS 1234 |
||||||
|
set PWM_RATE 400 |
||||||
|
# DJI ESC range |
||||||
|
set PWM_DISARMED 900 |
||||||
|
set PWM_MIN 1200 |
||||||
|
set PWM_MAX 1900 |
@ -0,0 +1,37 @@ |
|||||||
|
#!nsh |
||||||
|
# |
||||||
|
# Generic 10” Quad + geometry |
||||||
|
# |
||||||
|
# Maintainers: 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 |
||||||
|
|
||||||
|
set VEHICLE_TYPE mc |
||||||
|
set MIXER FMU_quad_+ |
||||||
|
|
||||||
|
set PWM_OUTPUTS 1234 |
||||||
|
set PWM_RATE 400 |
||||||
|
# DJI ESC range |
||||||
|
set PWM_DISARMED 900 |
||||||
|
set PWM_MIN 1200 |
||||||
|
set PWM_MAX 1900 |
@ -0,0 +1,37 @@ |
|||||||
|
#!nsh |
||||||
|
# |
||||||
|
# Generic 10” Hexa X geometry |
||||||
|
# |
||||||
|
# Maintainers: 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 |
||||||
|
|
||||||
|
set VEHICLE_TYPE mc |
||||||
|
set MIXER FMU_hexa_x |
||||||
|
|
||||||
|
set PWM_OUTPUTS 1234 |
||||||
|
set PWM_RATE 400 |
||||||
|
# DJI ESC range |
||||||
|
set PWM_DISARMED 900 |
||||||
|
set PWM_MIN 1200 |
||||||
|
set PWM_MAX 1900 |
@ -0,0 +1,37 @@ |
|||||||
|
#!nsh |
||||||
|
# |
||||||
|
# Generic 10” Hexa + geometry |
||||||
|
# |
||||||
|
# Maintainers: 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 |
||||||
|
|
||||||
|
set VEHICLE_TYPE mc |
||||||
|
set MIXER FMU_hexa_+ |
||||||
|
|
||||||
|
set PWM_OUTPUTS 1234 |
||||||
|
set PWM_RATE 400 |
||||||
|
# DJI ESC range |
||||||
|
set PWM_DISARMED 900 |
||||||
|
set PWM_MIN 1200 |
||||||
|
set PWM_MAX 1900 |
@ -0,0 +1,37 @@ |
|||||||
|
#!nsh |
||||||
|
# |
||||||
|
# Generic 10” Octo X geometry |
||||||
|
# |
||||||
|
# Maintainers: 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 |
||||||
|
|
||||||
|
set VEHICLE_TYPE mc |
||||||
|
set MIXER FMU_octo_x |
||||||
|
|
||||||
|
set PWM_OUTPUTS 1234 |
||||||
|
set PWM_RATE 400 |
||||||
|
# DJI ESC range |
||||||
|
set PWM_DISARMED 900 |
||||||
|
set PWM_MIN 1200 |
||||||
|
set PWM_MAX 1900 |
@ -0,0 +1,37 @@ |
|||||||
|
#!nsh |
||||||
|
# |
||||||
|
# Generic 10” Octo + geometry |
||||||
|
# |
||||||
|
# Maintainers: 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 |
||||||
|
|
||||||
|
set VEHICLE_TYPE mc |
||||||
|
set MIXER FMU_octo_+ |
||||||
|
|
||||||
|
set PWM_OUTPUTS 1234 |
||||||
|
set PWM_RATE 400 |
||||||
|
# DJI ESC range |
||||||
|
set PWM_DISARMED 900 |
||||||
|
set PWM_MIN 1200 |
||||||
|
set PWM_MAX 1900 |
@ -1,9 +0,0 @@ |
|||||||
#!nsh |
|
||||||
|
|
||||||
cp /etc/extras/px4io-v2_default.bin /fs/microsd/px4io.loaded |
|
||||||
if cmp /etc/extras/px4io-v2_default.bin /fs/microsd/px4io.loaded |
|
||||||
then |
|
||||||
echo "CMP returned true" |
|
||||||
else |
|
||||||
echo "CMP returned false" |
|
||||||
fi |
|
Loading…
Reference in new issue