mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 01:12:31 +00:00
Add Steadidrone MAVRIK mixer and gains.
This commit is contained in:
committed by
Lorenz Meier
parent
86c8308e98
commit
9a8050cc11
41
ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik
Normal file
41
ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik
Normal file
@@ -0,0 +1,41 @@
|
|||||||
|
#!nsh
|
||||||
|
#
|
||||||
|
# @name Steadidrone MAVRIK
|
||||||
|
#
|
||||||
|
# @type Octo Coax Wide
|
||||||
|
#
|
||||||
|
# @maintainer Simon Wilks <simon@uaventure.com>
|
||||||
|
#
|
||||||
|
|
||||||
|
sh /etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
|
if [ $AUTOCNF == yes ]
|
||||||
|
then
|
||||||
|
param set MC_PITCH_P 4.0
|
||||||
|
param set MC_PITCHRATE_P 0.24
|
||||||
|
param set MC_PITCHRATE_I 0.09
|
||||||
|
param set MC_PITCHRATE_D 0.013
|
||||||
|
param set MC_PITCHRATE_MAX 180.0
|
||||||
|
|
||||||
|
param set MC_ROLL_P 4.0
|
||||||
|
param set MC_ROLLRATE_P 0.16
|
||||||
|
param set MC_ROLLRATE_I 0.07
|
||||||
|
param set MC_ROLLRATE_D 0.009
|
||||||
|
param set MC_ROLLRATE_MAX 180.0
|
||||||
|
|
||||||
|
param set MC_YAW_P 3.0
|
||||||
|
param set MC_YAWRATE_P 0.2
|
||||||
|
param set MC_YAWRATE_I 0.1
|
||||||
|
param set MC_YAWRATE_D 0.0
|
||||||
|
param set MC_YAW_FF 0.5
|
||||||
|
|
||||||
|
param set MPC_HOLD_MAX_XY 0.25
|
||||||
|
param set MPC_THR_MIN 0.15
|
||||||
|
param set MPC_Z_VEL_MAX 2.0
|
||||||
|
|
||||||
|
param set BAT_N_CELLS 4
|
||||||
|
fi
|
||||||
|
|
||||||
|
set MIXER octo_cox_w
|
||||||
|
|
||||||
|
set PWM_OUT 12345678
|
||||||
@@ -692,7 +692,7 @@ then
|
|||||||
then
|
then
|
||||||
set MAV_TYPE 14
|
set MAV_TYPE 14
|
||||||
fi
|
fi
|
||||||
if [ $MIXER == octo_cox ]
|
if [ $MIXER == octo_cox -o $MIXER == octo_cox_w ]
|
||||||
then
|
then
|
||||||
set MAV_TYPE 14
|
set MAV_TYPE 14
|
||||||
fi
|
fi
|
||||||
|
|||||||
3
ROMFS/px4fmu_common/mixers/octo_cox_w.main.mix
Normal file
3
ROMFS/px4fmu_common/mixers/octo_cox_w.main.mix
Normal file
@@ -0,0 +1,3 @@
|
|||||||
|
# Octo coaxial with wide arms
|
||||||
|
|
||||||
|
R: 8cw 10000 10000 10000 0
|
||||||
@@ -180,6 +180,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
|
|||||||
} else if (!strcmp(geomname, "8c")) {
|
} else if (!strcmp(geomname, "8c")) {
|
||||||
geometry = MultirotorGeometry::OCTA_COX;
|
geometry = MultirotorGeometry::OCTA_COX;
|
||||||
|
|
||||||
|
} else if (!strcmp(geomname, "8cw")) {
|
||||||
|
geometry = MultirotorGeometry::OCTA_COX_WIDE;
|
||||||
|
|
||||||
} else if (!strcmp(geomname, "2-")) {
|
} else if (!strcmp(geomname, "2-")) {
|
||||||
geometry = MultirotorGeometry::TWIN_ENGINE;
|
geometry = MultirotorGeometry::TWIN_ENGINE;
|
||||||
|
|
||||||
|
|||||||
@@ -157,6 +157,17 @@ octa_cox = [
|
|||||||
[-135, CW],
|
[-135, CW],
|
||||||
]
|
]
|
||||||
|
|
||||||
|
octa_cox_wide = [
|
||||||
|
[ 68, CCW],
|
||||||
|
[ -68, CW],
|
||||||
|
[-129, CCW],
|
||||||
|
[ 129, CW],
|
||||||
|
[ -68, CCW],
|
||||||
|
[ 68, CW],
|
||||||
|
[ 129, CCW],
|
||||||
|
[-129, CW],
|
||||||
|
]
|
||||||
|
|
||||||
twin_engine = [
|
twin_engine = [
|
||||||
[ 90, 0.0],
|
[ 90, 0.0],
|
||||||
[-90, 0.0],
|
[-90, 0.0],
|
||||||
@@ -169,7 +180,7 @@ tri_y = [
|
|||||||
]
|
]
|
||||||
|
|
||||||
|
|
||||||
tables = [quad_x, quad_h, quad_plus, quad_v, quad_wide, quad_deadcat, hex_x, hex_plus, hex_cox, octa_x, octa_plus, octa_cox, twin_engine, tri_y]
|
tables = [quad_x, quad_h, quad_plus, quad_v, quad_wide, quad_deadcat, hex_x, hex_plus, hex_cox, octa_x, octa_plus, octa_cox, octa_cox_wide, twin_engine, tri_y]
|
||||||
|
|
||||||
def variableName(variable):
|
def variableName(variable):
|
||||||
for variableName, value in list(globals().items()):
|
for variableName, value in list(globals().items()):
|
||||||
|
|||||||
Reference in New Issue
Block a user