Merge pull request #1591 from anton-matosov/master

Multitables v3
This commit is contained in:
Lorenz Meier 2015-01-06 07:09:30 +01:00
commit 88d7c4e447
10 changed files with 284 additions and 278 deletions

1
.gitignore vendored
View File

@ -40,3 +40,4 @@ tags
*.orig
Firmware.zip
unittests/build
*.generated.h

View File

@ -4,7 +4,10 @@
language: cpp
before_script:
- sudo apt-get update -q
- sudo add-apt-repository --yes ppa:ubuntu-toolchain-r/test
- sudo apt-get update -qq
- if [ "$CXX" = "g++" ]; then sudo apt-get install -qq g++-4.8 gcc-4.8 libstdc++-4.8-dev; fi
- if [ "$CXX" = "g++" ]; then export CXX="g++-4.8" CC="gcc-4.8"; fi
# Travis specific tools
- sudo apt-get install s3cmd grep zip mailutils
# General toolchain dependencies
@ -39,6 +42,7 @@ script:
- arm-none-eabi-gcc --version
- echo 'Running Tests..' && echo -en 'travis_fold:start:script.1\\r'
- make tests
- cat src/modules/systemlib/mixer/mixer_multirotor.generated.h
- echo -en 'travis_fold:end:script.1\\r'
- echo 'Building NuttX..' && echo -en 'travis_fold:start:script.2\\r'
- make archives

View File

@ -1,5 +1,4 @@
SRCS = adc.c \
controls.c \
dsm.c \
@ -24,3 +23,7 @@ ifeq ($(BOARD),px4io-v2)
SRCS += serial.c \
../systemlib/hx_stream.c
endif
SELF_DIR := $(dir $(lastword $(MAKEFILE_LIST)))
include $(SELF_DIR)../systemlib/mixer/multi_tables.mk

View File

@ -441,6 +441,15 @@ private:
SimpleMixer operator=(const SimpleMixer&);
};
/**
* 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.
*
@ -450,27 +459,6 @@ private:
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,
TWIN_ENGINE, /**< VTOL: one engine on each wing */
MAX_GEOMETRY
};
/**
* Precalculated rotor mix.
*/
@ -498,7 +486,7 @@ public:
*/
MultirotorMixer(ControlCallback control_cb,
uintptr_t cb_handle,
Geometry geometry,
MultirotorGeometry geometry,
float roll_scale,
float pitch_scale,
float yaw_scale,

View File

@ -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>
@ -72,125 +75,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.000000 },
{ 0.707107, -0.707107, 1.000000 },
{ 0.707107, 0.707107, -1.000000 },
{ -0.707107, -0.707107, -1.000000 },
};
const MultirotorMixer::Rotor _config_quad_plus[] = {
{ -1.000000, 0.000000, 1.000000 },
{ 1.000000, 0.000000, 1.000000 },
{ 0.000000, 1.000000, -1.000000 },
{ -0.000000, -1.000000, -1.000000 },
};
const MultirotorMixer::Rotor _config_quad_v[] = {
{ -0.322266, 0.946649, 0.424200 },
{ 0.322266, 0.946649, 1.000000 },
{ 0.322266, 0.946649, -0.424200 },
{ -0.322266, 0.946649, -1.000000 },
};
const MultirotorMixer::Rotor _config_quad_wide[] = {
{ -0.927184, 0.374607, 1.000000 },
{ 0.777146, -0.629320, 1.000000 },
{ 0.927184, 0.374607, -1.000000 },
{ -0.777146, -0.629320, -1.000000 },
};
const MultirotorMixer::Rotor _config_hex_x[] = {
{ -1.000000, 0.000000, -1.000000 },
{ 1.000000, 0.000000, 1.000000 },
{ 0.500000, 0.866025, -1.000000 },
{ -0.500000, -0.866025, 1.000000 },
{ -0.500000, 0.866025, 1.000000 },
{ 0.500000, -0.866025, -1.000000 },
};
const MultirotorMixer::Rotor _config_hex_plus[] = {
{ 0.000000, 1.000000, -1.000000 },
{ -0.000000, -1.000000, 1.000000 },
{ 0.866025, -0.500000, -1.000000 },
{ -0.866025, 0.500000, 1.000000 },
{ 0.866025, 0.500000, 1.000000 },
{ -0.866025, -0.500000, -1.000000 },
};
const MultirotorMixer::Rotor _config_hex_cox[] = {
{ -0.866025, 0.500000, -1.000000 },
{ -0.866025, 0.500000, 1.000000 },
{ -0.000000, -1.000000, -1.000000 },
{ -0.000000, -1.000000, 1.000000 },
{ 0.866025, 0.500000, -1.000000 },
{ 0.866025, 0.500000, 1.000000 },
};
const MultirotorMixer::Rotor _config_octa_x[] = {
{ -0.382683, 0.923880, -1.000000 },
{ 0.382683, -0.923880, -1.000000 },
{ -0.923880, 0.382683, 1.000000 },
{ -0.382683, -0.923880, 1.000000 },
{ 0.382683, 0.923880, 1.000000 },
{ 0.923880, -0.382683, 1.000000 },
{ 0.923880, 0.382683, -1.000000 },
{ -0.923880, -0.382683, -1.000000 },
};
const MultirotorMixer::Rotor _config_octa_plus[] = {
{ 0.000000, 1.000000, -1.000000 },
{ -0.000000, -1.000000, -1.000000 },
{ -0.707107, 0.707107, 1.000000 },
{ -0.707107, -0.707107, 1.000000 },
{ 0.707107, 0.707107, 1.000000 },
{ 0.707107, -0.707107, 1.000000 },
{ 1.000000, 0.000000, -1.000000 },
{ -1.000000, 0.000000, -1.000000 },
};
const MultirotorMixer::Rotor _config_octa_cox[] = {
{ -0.707107, 0.707107, 1.000000 },
{ 0.707107, 0.707107, -1.000000 },
{ 0.707107, -0.707107, 1.000000 },
{ -0.707107, -0.707107, -1.000000 },
{ 0.707107, 0.707107, 1.000000 },
{ -0.707107, 0.707107, -1.000000 },
{ -0.707107, -0.707107, 1.000000 },
{ 0.707107, -0.707107, -1.000000 },
};
const MultirotorMixer::Rotor _config_twin_engine[] = {
{ -1.000000, 0.000000, 0.000000 },
{ 1.000000, 0.000000, 0.000000 },
};
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],
&_config_twin_engine[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 */
2, /* twin_engine */
};
}
MultirotorMixer::MultirotorMixer(ControlCallback control_cb,
uintptr_t cb_handle,
Geometry geometry,
MultirotorGeometry geometry,
float roll_scale,
float pitch_scale,
float yaw_scale,
@ -200,8 +89,8 @@ 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])
_rotor_count(_config_rotor_count[(MultirotorGeometryUnderlyingType)geometry]),
_rotors(_config_index[(MultirotorGeometryUnderlyingType)geometry])
{
}
@ -212,7 +101,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;
@ -252,37 +141,37 @@ 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, "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 = MultirotorMixer::TWIN_ENGINE;
geometry = MultirotorGeometry::TWIN_ENGINE;
} else {
debug("unrecognised geometry '%s'", geomname);
return nullptr;

View File

@ -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

View File

@ -1,135 +1,197 @@
#!/usr/bin/tclsh
#!/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
#
proc rad {a} { expr ($a / 360.0) * 2 * acos(-1) }
proc rcos {a} { expr cos([rad $a])}
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_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],
]
def variableName(variable):
for variableName, value in list(globals().iteritems()):
if value is variable:
return variableName
tables = [quad_x, quad_plus, quad_v, quad_wide, hex_x, hex_plus, hex_cox, octa_x, octa_plus, octa_cox, twin_engine]
set quad_x {
45 CCW
-135 CCW
-45 CW
135 CW
}
def printEnum():
print "enum class MultirotorGeometry : MultirotorGeometryUnderlyingType {"
for table in tables:
print "\t{},".format(variableName(table).upper())
set quad_plus {
90 CCW
-90 CCW
0 CW
180 CW
}
print "\n\tMAX_GEOMETRY"
print "}; // enum class MultirotorGeometry\n"
set quad_v {
18.8 0.4242
-18.8 1.0
-18.8 -0.4242
18.8 -1.0
}
def printScaleTables():
for table in tables:
print "const MultirotorMixer::Rotor _config_{}[] = {{".format(variableName(table))
for (angle, yawScale) in table:
rollScale = rcos(angle + 90)
pitchScale = rcos(angle)
print "\t{{ {:9f}, {:9f}, {:9f} }},".format(rollScale, pitchScale, yawScale)
print "};\n"
def printScaleTablesIndex():
print "const MultirotorMixer::Rotor *_config_index[] = {"
for table in tables:
print "\t&_config_{}[0],".format(variableName(table))
print "};\n"
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
}
def printScaleTablesCounts():
print "const unsigned _config_rotor_count[] = {"
for table in tables:
print "\t{}, /* {} */".format(len(table), variableName(table))
print "};\n"
set hex_plus {
0 CW
180 CCW
-120 CW
60 CCW
-60 CCW
120 CW
}
printEnum()
set hex_cox {
60 CW
60 CCW
180 CW
180 CCW
-60 CW
-60 CCW
}
print "namespace {"
printScaleTables()
printScaleTablesIndex()
printScaleTablesCounts()
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 twin_engine {
90 0.0
-90 0.0
}
set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus hex_cox octa_x octa_plus octa_cox twin_engine}
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %9.6f }," [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
} elseif {$dir == "CCW"} {
set dd 1.0
} else {
set dd $dir
}
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 "};"
print "} // anonymous namespace\n"
print "#endif /* _MIXER_MULTI_TABLES */"
print ""

View File

@ -0,0 +1,43 @@
############################################################################
#
# 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)))
# 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 : $(SELF_DIR)multi_tables
$(SELF_DIR)multi_tables > $(SELF_DIR)mixer_multirotor.generated.h
$(SELF_DIR)multi_tables

View File

@ -19,6 +19,16 @@ function(add_gtest)
endforeach()
endfunction()
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
else()
message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
endif()
# add each test
# todo: add mixer_test sbus2_test st24_test sf0x_test

View File

@ -1,7 +1,7 @@
CC=g++
CC=$(CXX)
CFLAGS=-I. -I../src/modules -I ../src/include -I../src/drivers \
-I../src -I../src/lib -D__EXPORT="" -Dnullptr="0" -lm
-I../src -I../src/lib -D__EXPORT="" -Dnullptr="0" -lm -std=c++11
# Points to the root of Google Test, relative to where this file is.
# Remember to tweak this if you move this file.
@ -53,6 +53,8 @@ MIXER_FILES=../src/systemcmds/tests/test_mixer.cpp \
hrt.cpp \
mixer_test.cpp
include ../src/modules/systemlib/mixer/multi_tables.mk
SBUS2_FILES=../src/modules/px4iofirmware/sbus.c \
hrt.cpp \
sbus2_test.cpp