aboutsummaryrefslogtreecommitdiff
path: root/src/modules/systemlib/mixer
diff options
context:
space:
mode:
authorTrent Lukaczyk <aerialhedgehog@gmail.com>2015-01-31 15:00:16 -0800
committerTrent Lukaczyk <aerialhedgehog@gmail.com>2015-01-31 15:00:16 -0800
commitd036fa10c1f26576bac27c130843fac45098b736 (patch)
tree2613b11c0e0244576aa024e913f42f5a42767b33 /src/modules/systemlib/mixer
parent48669846724f6afcf00620a197a26d00107c1076 (diff)
parenta2a244584e36a0e9ffdb93a0dda8473baf8344d3 (diff)
downloadpx4-firmware-d036fa10c1f26576bac27c130843fac45098b736.tar.gz
px4-firmware-d036fa10c1f26576bac27c130843fac45098b736.tar.bz2
px4-firmware-d036fa10c1f26576bac27c130843fac45098b736.zip
Merge remote-tracking branch 'upstream/master'
Diffstat (limited to 'src/modules/systemlib/mixer')
-rw-r--r--src/modules/systemlib/mixer/mixer.h30
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp147
-rw-r--r--src/modules/systemlib/mixer/module.mk6
-rwxr-xr-xsrc/modules/systemlib/mixer/multi_tables127
-rw-r--r--src/modules/systemlib/mixer/multi_tables.mk42
-rwxr-xr-xsrc/modules/systemlib/mixer/multi_tables.py213
6 files changed, 296 insertions, 269 deletions
diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h
index 17989558e..67ef521b4 100644
--- a/src/modules/systemlib/mixer/mixer.h
+++ b/src/modules/systemlib/mixer/mixer.h
@@ -442,6 +442,14 @@ private:
};
/**
+ * Supported multirotor geometries.
+ *
+ * Values are generated by the multi_tables script and placed to mixer_multirotor.generated.h
+ */
+typedef unsigned int MultirotorGeometryUnderlyingType;
+enum class MultirotorGeometry : MultirotorGeometryUnderlyingType;
+
+/**
* Multi-rotor mixer for pre-defined vehicle geometries.
*
* Collects four inputs (roll, pitch, yaw, thrust) and mixes them to
@@ -451,32 +459,14 @@ class __EXPORT MultirotorMixer : public Mixer
{
public:
/**
- * Supported multirotor geometries.
- *
- * XXX add more
- */
- enum Geometry {
- QUAD_X = 0, /**< quad in X configuration */
- QUAD_PLUS, /**< quad in + configuration */
- QUAD_V, /**< quad in V configuration */
- QUAD_WIDE, /**< quad in wide configuration */
- HEX_X, /**< hex in X configuration */
- HEX_PLUS, /**< hex in + configuration */
- HEX_COX,
- OCTA_X,
- OCTA_PLUS,
- OCTA_COX,
-
- MAX_GEOMETRY
- };
- /**
* Precalculated rotor mix.
*/
struct Rotor {
float roll_scale; /**< scales roll for this rotor */
float pitch_scale; /**< scales pitch for this rotor */
float yaw_scale; /**< scales yaw for this rotor */
+ float out_scale; /**< scales total out for this rotor */
};
/**
@@ -497,7 +487,7 @@ public:
*/
MultirotorMixer(ControlCallback control_cb,
uintptr_t cb_handle,
- Geometry geometry,
+ MultirotorGeometry geometry,
float roll_scale,
float pitch_scale,
float yaw_scale,
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index 57e17b67d..2ab5b5e8e 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -55,6 +55,9 @@
#include "mixer.h"
+// This file is generated by the multi_tables script which is invoked during the build process
+#include "mixer_multirotor.generated.h"
+
#define debug(fmt, args...) do { } while(0)
//#define debug(fmt, args...) do { printf("[mixer] " fmt "\n", ##args); } while(0)
//#include <debug.h>
@@ -73,117 +76,11 @@ float constrain(float val, float min, float max)
return (val < min) ? min : ((val > max) ? max : val);
}
-/*
- * These tables automatically generated by multi_tables - do not edit.
- */
-const MultirotorMixer::Rotor _config_quad_x[] = {
- { -0.707107, 0.707107, 1.00 },
- { 0.707107, -0.707107, 1.00 },
- { 0.707107, 0.707107, -1.00 },
- { -0.707107, -0.707107, -1.00 },
-};
-const MultirotorMixer::Rotor _config_quad_plus[] = {
- { -1.000000, 0.000000, 1.00 },
- { 1.000000, 0.000000, 1.00 },
- { 0.000000, 1.000000, -1.00 },
- { -0.000000, -1.000000, -1.00 },
-};
-const MultirotorMixer::Rotor _config_quad_v[] = {
- { -0.927184, 0.374607, 1.00 },
- { 0.694658, -0.719340, 1.00 },
- { 0.927184, 0.374607, -1.00 },
- { -0.694658, -0.719340, -1.00 },
-};
-const MultirotorMixer::Rotor _config_quad_wide[] = {
- { -0.927184, 0.374607, 1.00 },
- { 0.777146, -0.629320, 1.00 },
- { 0.927184, 0.374607, -1.00 },
- { -0.777146, -0.629320, -1.00 },
-};
-const MultirotorMixer::Rotor _config_hex_x[] = {
- { -1.000000, 0.000000, -1.00 },
- { 1.000000, 0.000000, 1.00 },
- { 0.500000, 0.866025, -1.00 },
- { -0.500000, -0.866025, 1.00 },
- { -0.500000, 0.866025, 1.00 },
- { 0.500000, -0.866025, -1.00 },
-};
-const MultirotorMixer::Rotor _config_hex_plus[] = {
- { 0.000000, 1.000000, -1.00 },
- { -0.000000, -1.000000, 1.00 },
- { 0.866025, -0.500000, -1.00 },
- { -0.866025, 0.500000, 1.00 },
- { 0.866025, 0.500000, 1.00 },
- { -0.866025, -0.500000, -1.00 },
-};
-const MultirotorMixer::Rotor _config_hex_cox[] = {
- { -0.866025, 0.500000, -1.00 },
- { -0.866025, 0.500000, 1.00 },
- { -0.000000, -1.000000, -1.00 },
- { -0.000000, -1.000000, 1.00 },
- { 0.866025, 0.500000, -1.00 },
- { 0.866025, 0.500000, 1.00 },
-};
-const MultirotorMixer::Rotor _config_octa_x[] = {
- { -0.382683, 0.923880, -1.00 },
- { 0.382683, -0.923880, -1.00 },
- { -0.923880, 0.382683, 1.00 },
- { -0.382683, -0.923880, 1.00 },
- { 0.382683, 0.923880, 1.00 },
- { 0.923880, -0.382683, 1.00 },
- { 0.923880, 0.382683, -1.00 },
- { -0.923880, -0.382683, -1.00 },
-};
-const MultirotorMixer::Rotor _config_octa_plus[] = {
- { 0.000000, 1.000000, -1.00 },
- { -0.000000, -1.000000, -1.00 },
- { -0.707107, 0.707107, 1.00 },
- { -0.707107, -0.707107, 1.00 },
- { 0.707107, 0.707107, 1.00 },
- { 0.707107, -0.707107, 1.00 },
- { 1.000000, 0.000000, -1.00 },
- { -1.000000, 0.000000, -1.00 },
-};
-const MultirotorMixer::Rotor _config_octa_cox[] = {
- { -0.707107, 0.707107, 1.00 },
- { 0.707107, 0.707107, -1.00 },
- { 0.707107, -0.707107, 1.00 },
- { -0.707107, -0.707107, -1.00 },
- { 0.707107, 0.707107, 1.00 },
- { -0.707107, 0.707107, -1.00 },
- { -0.707107, -0.707107, 1.00 },
- { 0.707107, -0.707107, -1.00 },
-};
-const MultirotorMixer::Rotor *_config_index[MultirotorMixer::MAX_GEOMETRY] = {
- &_config_quad_x[0],
- &_config_quad_plus[0],
- &_config_quad_v[0],
- &_config_quad_wide[0],
- &_config_hex_x[0],
- &_config_hex_plus[0],
- &_config_hex_cox[0],
- &_config_octa_x[0],
- &_config_octa_plus[0],
- &_config_octa_cox[0],
-};
-const unsigned _config_rotor_count[MultirotorMixer::MAX_GEOMETRY] = {
- 4, /* quad_x */
- 4, /* quad_plus */
- 4, /* quad_v */
- 4, /* quad_wide */
- 6, /* hex_x */
- 6, /* hex_plus */
- 6, /* hex_cox */
- 8, /* octa_x */
- 8, /* octa_plus */
- 8, /* octa_cox */
-};
-
-}
+} // anonymous namespace
MultirotorMixer::MultirotorMixer(ControlCallback control_cb,
uintptr_t cb_handle,
- Geometry geometry,
+ MultirotorGeometry geometry,
float roll_scale,
float pitch_scale,
float yaw_scale,
@@ -193,8 +90,9 @@ MultirotorMixer::MultirotorMixer(ControlCallback control_cb,
_pitch_scale(pitch_scale),
_yaw_scale(yaw_scale),
_idle_speed(-1.0f + idle_speed * 2.0f), /* shift to output range here to avoid runtime calculation */
- _rotor_count(_config_rotor_count[geometry]),
- _rotors(_config_index[geometry])
+ _limits_pub(),
+ _rotor_count(_config_rotor_count[(MultirotorGeometryUnderlyingType)geometry]),
+ _rotors(_config_index[(MultirotorGeometryUnderlyingType)geometry])
{
}
@@ -205,7 +103,7 @@ MultirotorMixer::~MultirotorMixer()
MultirotorMixer *
MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, const char *buf, unsigned &buflen)
{
- MultirotorMixer::Geometry geometry;
+ MultirotorGeometry geometry;
char geomname[8];
int s[4];
int used;
@@ -245,35 +143,40 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
debug("remaining in buf: %d, first char: %c", buflen, buf[0]);
if (!strcmp(geomname, "4+")) {
- geometry = MultirotorMixer::QUAD_PLUS;
+ geometry = MultirotorGeometry::QUAD_PLUS;
} else if (!strcmp(geomname, "4x")) {
- geometry = MultirotorMixer::QUAD_X;
+ geometry = MultirotorGeometry::QUAD_X;
} else if (!strcmp(geomname, "4v")) {
- geometry = MultirotorMixer::QUAD_V;
+ geometry = MultirotorGeometry::QUAD_V;
} else if (!strcmp(geomname, "4w")) {
- geometry = MultirotorMixer::QUAD_WIDE;
+ geometry = MultirotorGeometry::QUAD_WIDE;
+
+ } else if (!strcmp(geomname, "4dc")) {
+ geometry = MultirotorGeometry::QUAD_DEADCAT;
} else if (!strcmp(geomname, "6+")) {
- geometry = MultirotorMixer::HEX_PLUS;
+ geometry = MultirotorGeometry::HEX_PLUS;
} else if (!strcmp(geomname, "6x")) {
- geometry = MultirotorMixer::HEX_X;
+ geometry = MultirotorGeometry::HEX_X;
} else if (!strcmp(geomname, "6c")) {
- geometry = MultirotorMixer::HEX_COX;
+ geometry = MultirotorGeometry::HEX_COX;
} else if (!strcmp(geomname, "8+")) {
- geometry = MultirotorMixer::OCTA_PLUS;
+ geometry = MultirotorGeometry::OCTA_PLUS;
} else if (!strcmp(geomname, "8x")) {
- geometry = MultirotorMixer::OCTA_X;
+ geometry = MultirotorGeometry::OCTA_X;
} else if (!strcmp(geomname, "8c")) {
- geometry = MultirotorMixer::OCTA_COX;
+ geometry = MultirotorGeometry::OCTA_COX;
+ } else if (!strcmp(geomname, "2-")) {
+ geometry = MultirotorGeometry::TWIN_ENGINE;
} else {
debug("unrecognised geometry '%s'", geomname);
return nullptr;
@@ -314,6 +217,8 @@ MultirotorMixer::mix(float *outputs, unsigned space)
pitch * _rotors[i].pitch_scale +
thrust;
+ out *= _rotors[i].out_scale;
+
/* limit yaw if it causes outputs clipping */
if (out >= 0.0f && out < -yaw * _rotors[i].yaw_scale) {
yaw = -out / _rotors[i].yaw_scale;
diff --git a/src/modules/systemlib/mixer/module.mk b/src/modules/systemlib/mixer/module.mk
index fc7485e20..3fd07f5ba 100644
--- a/src/modules/systemlib/mixer/module.mk
+++ b/src/modules/systemlib/mixer/module.mk
@@ -31,13 +31,17 @@
#
############################################################################
+
#
# mixer library
#
LIBNAME = mixerlib
-
+
SRCS = mixer.cpp \
mixer_group.cpp \
mixer_multirotor.cpp \
mixer_simple.cpp \
mixer_load.c
+
+SELF_DIR := $(dir $(lastword $(MAKEFILE_LIST)))
+include $(SELF_DIR)multi_tables.mk
diff --git a/src/modules/systemlib/mixer/multi_tables b/src/modules/systemlib/mixer/multi_tables
deleted file mode 100755
index b5698036e..000000000
--- a/src/modules/systemlib/mixer/multi_tables
+++ /dev/null
@@ -1,127 +0,0 @@
-#!/usr/bin/tclsh
-#
-# Generate multirotor mixer scale tables compatible with the ArduCopter layout
-#
-
-proc rad {a} { expr ($a / 360.0) * 2 * acos(-1) }
-proc rcos {a} { expr cos([rad $a])}
-
-set quad_x {
- 45 CCW
- -135 CCW
- -45 CW
- 135 CW
-}
-
-set quad_plus {
- 90 CCW
- -90 CCW
- 0 CW
- 180 CW
-}
-
-set quad_v {
- 68 CCW
- -136 CCW
- -68 CW
- 136 CW
-}
-
-set quad_wide {
- 68 CCW
- -129 CCW
- -68 CW
- 129 CW
-}
-
-set hex_x {
- 90 CW
- -90 CCW
- -30 CW
- 150 CCW
- 30 CCW
- -150 CW
-}
-
-set hex_plus {
- 0 CW
- 180 CCW
- -120 CW
- 60 CCW
- -60 CCW
- 120 CW
-}
-
-set hex_cox {
- 60 CW
- 60 CCW
- 180 CW
- 180 CCW
- -60 CW
- -60 CCW
-}
-
-set octa_x {
- 22.5 CW
- -157.5 CW
- 67.5 CCW
- 157.5 CCW
- -22.5 CCW
- -112.5 CCW
- -67.5 CW
- 112.5 CW
-}
-
-set octa_plus {
- 0 CW
- 180 CW
- 45 CCW
- 135 CCW
- -45 CCW
- -135 CCW
- -90 CW
- 90 CW
-}
-
-set octa_cox {
- 45 CCW
- -45 CW
- -135 CCW
- 135 CW
- -45 CCW
- 45 CW
- 135 CCW
- -135 CW
-}
-
-set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus hex_cox octa_x octa_plus octa_cox}
-
-proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
-
-foreach table $tables {
- puts [format "const MultirotorMixer::Rotor _config_%s\[\] = {" $table]
-
- upvar #0 $table angles
- foreach {angle dir} $angles {
- if {$dir == "CW"} {
- set dd 1.0
- } else {
- set dd -1.0
- }
- factors $angle $dd
- }
- puts "};"
-}
-
-puts "const MultirotorMixer::Rotor *_config_index\[MultirotorMixer::MAX_GEOMETRY\] = {"
-foreach table $tables {
- puts [format "\t&_config_%s\[0\]," $table]
-}
-puts "};"
-
-puts "const unsigned _config_rotor_count\[MultirotorMixer::MAX_GEOMETRY\] = {"
-foreach table $tables {
- upvar #0 $table angles
- puts [format "\t%u, /* %s */" [expr [llength $angles] / 2] $table]
-}
-puts "};"
diff --git a/src/modules/systemlib/mixer/multi_tables.mk b/src/modules/systemlib/mixer/multi_tables.mk
new file mode 100644
index 000000000..c537c83a4
--- /dev/null
+++ b/src/modules/systemlib/mixer/multi_tables.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2014 Anton Matosov <anton.matosov@gmail.com>. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+
+SELF_DIR := $(dir $(lastword $(MAKEFILE_LIST)))
+MULTI_TABLES := $(SELF_DIR)multi_tables.py
+
+# Add explicit dependency, as implicit one doesn't work often.
+$(SELF_DIR)mixer_multirotor.cpp : $(SELF_DIR)mixer_multirotor.generated.h
+
+$(SELF_DIR)mixer_multirotor.generated.h : $(MULTI_TABLES)
+ $(Q) $(PYTHON) $(MULTI_TABLES) > $(SELF_DIR)mixer_multirotor.generated.h
diff --git a/src/modules/systemlib/mixer/multi_tables.py b/src/modules/systemlib/mixer/multi_tables.py
new file mode 100755
index 000000000..ba59e0536
--- /dev/null
+++ b/src/modules/systemlib/mixer/multi_tables.py
@@ -0,0 +1,213 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Generate multirotor mixer scale tables compatible with the ArduCopter layout
+#
+
+# for python2.7 compatibility
+from __future__ import print_function
+
+import math
+
+print("/*")
+print("* This file is automatically generated by multi_tables - do not edit.")
+print("*/")
+print("")
+print("#ifndef _MIXER_MULTI_TABLES")
+print("#define _MIXER_MULTI_TABLES")
+print("")
+
+def rcos(angleInRadians):
+ return math.cos(math.radians(angleInRadians))
+
+CCW = 1.0
+CW = -CCW
+
+quad_x = [
+ [ 45, CCW],
+ [-135, CCW],
+ [-45, CW],
+ [135, CW],
+]
+
+quad_plus = [
+ [ 90, CCW],
+ [ -90, CCW],
+ [ 0, CW],
+ [ 180, CW],
+]
+
+quad_deadcat = [
+ [ 63, CCW, 1.0],
+ [-135, CCW, 0.964],
+ [ -63, CW, 1.0],
+ [ 135, CW, 0.964],
+]
+
+quad_v = [
+ [ 18.8, 0.4242],
+ [ -18.8, 1.0],
+ [ -18.8, -0.4242],
+ [ 18.8, -1.0],
+]
+
+quad_wide = [
+ [ 68, CCW],
+ [ -129, CCW],
+ [ -68, CW],
+ [ 129, CW],
+]
+
+hex_x = [
+ [ 90, CW],
+ [ -90, CCW],
+ [ -30, CW],
+ [ 150, CCW],
+ [ 30, CCW],
+ [-150, CW],
+]
+
+hex_plus = [
+ [ 0, CW],
+ [ 180, CCW],
+ [-120, CW],
+ [ 60, CCW],
+ [ -60, CCW],
+ [ 120, CW],
+]
+
+hex_cox = [
+ [ 60, CW],
+ [ 60, CCW],
+ [ 180, CW],
+ [ 180, CCW],
+ [ -60, CW],
+ [ -60, CCW],
+]
+
+octa_x = [
+ [ 22.5, CW],
+ [-157.5, CW],
+ [ 67.5, CCW],
+ [ 157.5, CCW],
+ [ -22.5, CCW],
+ [-112.5, CCW],
+ [ -67.5, CW],
+ [ 112.5, CW],
+]
+
+octa_plus = [
+ [ 0, CW],
+ [ 180, CW],
+ [ 45, CCW],
+ [ 135, CCW],
+ [ -45, CCW],
+ [-135, CCW],
+ [ -90, CW],
+ [ 90, CW],
+]
+
+octa_cox = [
+ [ 45, CCW],
+ [ -45, CW],
+ [-135, CCW],
+ [ 135, CW],
+ [ -45, CCW],
+ [ 45, CW],
+ [ 135, CCW],
+ [-135, CW],
+]
+
+twin_engine = [
+ [ 90, 0.0],
+ [-90, 0.0],
+]
+
+
+tables = [quad_x, quad_plus, quad_v, quad_wide, quad_deadcat, hex_x, hex_plus, hex_cox, octa_x, octa_plus, octa_cox, twin_engine]
+
+def variableName(variable):
+ for variableName, value in list(globals().items()):
+ if value is variable:
+ return variableName
+
+def unpackScales(scalesList):
+ if len(scalesList) == 2:
+ scalesList += [1.0] #Add thrust scale
+ return scalesList
+
+def printEnum():
+ print("enum class MultirotorGeometry : MultirotorGeometryUnderlyingType {")
+ for table in tables:
+ print("\t{},".format(variableName(table).upper()))
+
+ print("\n\tMAX_GEOMETRY")
+ print("}; // enum class MultirotorGeometry\n")
+
+def printScaleTables():
+ for table in tables:
+ print("const MultirotorMixer::Rotor _config_{}[] = {{".format(variableName(table)))
+ for row in table:
+ angle, yawScale, thrustScale = unpackScales(row)
+ rollScale = rcos(angle + 90)
+ pitchScale = rcos(angle)
+ print("\t{{ {:9f}, {:9f}, {:9f}, {:9f} }},".format(rollScale, pitchScale, yawScale, thrustScale))
+ print("};\n")
+
+def printScaleTablesIndex():
+ print("const MultirotorMixer::Rotor *_config_index[] = {")
+ for table in tables:
+ print("\t&_config_{}[0],".format(variableName(table)))
+ print("};\n")
+
+
+def printScaleTablesCounts():
+ print("const unsigned _config_rotor_count[] = {")
+ for table in tables:
+ print("\t{}, /* {} */".format(len(table), variableName(table)))
+ print("};\n")
+
+
+
+printEnum()
+
+print("namespace {")
+printScaleTables()
+printScaleTablesIndex()
+printScaleTablesCounts()
+
+print("} // anonymous namespace\n")
+print("#endif /* _MIXER_MULTI_TABLES */")
+print("")