ControlMath: switch to gtest for unit tessting

This commit is contained in:
Matthias Grob 2019-10-22 15:50:48 +02:00
parent ad60f6d786
commit d60e1e2774
9 changed files with 184 additions and 258 deletions

View File

@ -82,7 +82,6 @@ def main():
do_test(args.device, args.baudrate, "commander")
do_test(args.device, args.baudrate, "controllib")
do_test(args.device, args.baudrate, "conv")
do_test(args.device, args.baudrate, "ctlmath")
#do_test(args.device, args.baudrate, "dataman")
do_test(args.device, args.baudrate, "float")
do_test(args.device, args.baudrate, "hrt")

View File

@ -33,7 +33,7 @@
#=============================================================================
#
# px4_add_gtest
# px4_add_unit_gtest
#
# Adds a googletest unit test to the test_results target.
#

View File

@ -10,7 +10,6 @@ set(tests
commander
controllib
conv
ctlmath
dataman
file2
float

View File

@ -39,3 +39,5 @@ target_include_directories(PositionControl
PUBLIC
${CMAKE_CURRENT_SOURCE_DIR}
)
px4_add_unit_gtest(SRC ControlMathTest.cpp LINKLIBS PositionControl)

View File

@ -0,0 +1,181 @@
/****************************************************************************
*
* Copyright (C) 2019 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.
*
****************************************************************************/
#include <gtest/gtest.h>
#include <ControlMath.hpp>
#include <px4_defines.h>
using namespace matrix;
using namespace ControlMath;
TEST(ControlMathTest, ThrottleAttitudeMapping)
{
/* expected: zero roll, zero pitch, zero yaw, full thr mag
* reason: thrust pointing full upward */
Vector3f thr{0.0f, 0.0f, -1.0f};
float yaw = 0.0f;
vehicle_attitude_setpoint_s att{};
att = thrustToAttitude(thr, yaw);
EXPECT_EQ(att.roll_body, 0);
EXPECT_EQ(att.pitch_body, 0);
EXPECT_EQ(att.yaw_body, 0);
EXPECT_EQ(att.thrust_body[2], -1.f);
/* expected: same as before but with 90 yaw
* reason: only yaw changed */
yaw = M_PI_2_F;
att = thrustToAttitude(thr, yaw);
EXPECT_EQ(att.roll_body, 0);
EXPECT_EQ(att.pitch_body, 0);
EXPECT_EQ(att.yaw_body, M_PI_2_F);
EXPECT_EQ(att.thrust_body[2], -1.f);
/* expected: same as before but roll 180
* reason: thrust points straight down and order Euler
* order is: 1. roll, 2. pitch, 3. yaw */
thr = Vector3f(0.0f, 0.0f, 1.0f);
att = thrustToAttitude(thr, yaw);
EXPECT_NEAR(abs(att.roll_body), M_PI_F, 1e4f);
EXPECT_EQ(att.pitch_body, 0);
EXPECT_EQ(att.yaw_body, M_PI_2_F);
EXPECT_EQ(att.thrust_body[2], -1.f);
}
TEST(ControlMathTest, ConstrainXYPriorities)
{
float max = 5.0f;
// v0 already at max
Vector2f v0(max, 0);
Vector2f v1(v0(1), -v0(0));
Vector2f v_r = constrainXY(v0, v1, max);
EXPECT_EQ(v_r(0), max);
EXPECT_GT(v_r(0), 0);
EXPECT_EQ(v_r(1), 0);
// v1 exceeds max but v0 is zero
v0.zero();
v_r = constrainXY(v0, v1, max);
EXPECT_EQ(v_r(1), -max);
EXPECT_LT(v_r(1), 0);
EXPECT_EQ(v_r(0), 0);
v0 = Vector2f(0.5f, 0.5f);
v1 = Vector2f(0.5f, -0.5f);
v_r = constrainXY(v0, v1, max);
float diff = Vector2f(v_r - (v0 + v1)).length();
EXPECT_EQ(diff, 0);
// v0 and v1 exceed max and are perpendicular
v0 = Vector2f(4.0f, 0.0f);
v1 = Vector2f(0.0f, -4.0f);
v_r = constrainXY(v0, v1, max);
EXPECT_EQ(v_r(0), v0(0));
EXPECT_GT(v_r(0), 0);
float remaining = sqrtf(max * max - (v0(0) * v0(0)));
EXPECT_EQ(v_r(1), -remaining);
}
TEST(ControlMathTest, CrossSphereLine)
{
/* Testing 9 positions (+) around waypoints (o):
*
* Far + + +
*
* Near + + +
* On trajectory --+----o---------+---------o----+--
* prev curr
*
* Expected targets (1, 2, 3):
* Far + + +
*
*
* On trajectory -------1---------2---------3-------
*
*
* Near + + +
* On trajectory -------o---1---------2-----3-------
*
*
* On trajectory --+----o----1----+--------2/3---+-- */
Vector3f prev = Vector3f(0.0f, 0.0f, 0.0f);
Vector3f curr = Vector3f(0.0f, 0.0f, 2.0f);
Vector3f res;
bool retval = false;
// on line, near, before previous waypoint
retval = cross_sphere_line(Vector3f(0.0f, 0.0f, -0.5f), 1.0f, prev, curr, res);
EXPECT_TRUE(retval);
EXPECT_EQ(res, Vector3f(0.f, 0.f, 0.5f));
// on line, near, before target waypoint
retval = cross_sphere_line(Vector3f(0.0f, 0.0f, 1.0f), 1.0f, prev, curr, res);
EXPECT_TRUE(retval);
EXPECT_EQ(res, Vector3f(0.f, 0.f, 2.f));
// on line, near, after target waypoint
retval = cross_sphere_line(Vector3f(0.0f, 0.0f, 2.5f), 1.0f, prev, curr, res);
EXPECT_TRUE(retval);
EXPECT_EQ(res, Vector3f(0.f, 0.f, 2.f));
// near, before previous waypoint
retval = cross_sphere_line(Vector3f(0.0f, 0.5f, -0.5f), 1.0f, prev, curr, res);
EXPECT_TRUE(retval);
EXPECT_EQ(res, Vector3f(0.f, 0.f, 0.366025388f));
// near, before target waypoint
retval = cross_sphere_line(Vector3f(0.0f, 0.5f, 1.0f), 1.0f, prev, curr, res);
EXPECT_TRUE(retval);
EXPECT_EQ(res, Vector3f(0.f, 0.f, 1.866025448f));
// near, after target waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 0.5f, 2.5f), 1.0f, prev, curr, res);
EXPECT_TRUE(retval);
EXPECT_EQ(res, Vector3f(0.f, 0.f, 2.f));
// far, before previous waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 2.0f, -0.5f), 1.0f, prev, curr, res);
EXPECT_FALSE(retval);
EXPECT_EQ(res, Vector3f());
// far, before target waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 2.0f, 1.0f), 1.0f, prev, curr, res);
EXPECT_FALSE(retval);
EXPECT_EQ(res, Vector3f(0.f, 0.f, 1.f));
// far, after target waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 2.0f, 2.5f), 1.0f, prev, curr, res);
EXPECT_FALSE(retval);
EXPECT_EQ(res, Vector3f(0.f, 0.f, 2.f));
}

View File

@ -36,7 +36,6 @@ set(srcs
test_autodeclination.cpp
test_bezierQuad.cpp
test_bson.cpp
test_controlmath.cpp
test_conv.cpp
test_dataman.c
test_file.c

View File

@ -1,252 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2018-2019 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.
*
****************************************************************************/
/**
* @file test_controlmath.cpp
* Tests for the controls calculations.
*/
#include <unit_test.h>
#include <mc_pos_control/PositionControl/ControlMath.hpp>
#include <mathlib/mathlib.h>
#include <float.h>
#define SIGMA_SINGLE_OP 0.000001f
class ControlMathTest : public UnitTest
{
public:
virtual bool run_tests();
private:
bool testThrAttMapping();
bool testPrioritizeVector();
bool crossSphereLineTest();
};
bool ControlMathTest::run_tests()
{
ut_run_test(testThrAttMapping);
ut_run_test(testPrioritizeVector);
ut_run_test(crossSphereLineTest);
return (_tests_failed == 0);
}
bool ControlMathTest::testThrAttMapping()
{
/* expected: zero roll, zero pitch, zero yaw, full thr mag
* reasone: thrust pointing full upward
*/
matrix::Vector3f thr{0.0f, 0.0f, -1.0f};
float yaw = 0.0f;
vehicle_attitude_setpoint_s att = ControlMath::thrustToAttitude(thr, yaw);
ut_assert_true(att.roll_body < SIGMA_SINGLE_OP);
ut_assert_true(att.pitch_body < SIGMA_SINGLE_OP);
ut_assert_true(att.yaw_body < SIGMA_SINGLE_OP);
ut_assert_true(-att.thrust_body[2] - 1.0f < SIGMA_SINGLE_OP);
/* expected: same as before but with 90 yaw
* reason: only yaw changed
*/
yaw = M_PI_2_F;
att = ControlMath::thrustToAttitude(thr, yaw);
ut_assert_true(att.roll_body < SIGMA_SINGLE_OP);
ut_assert_true(att.pitch_body < SIGMA_SINGLE_OP);
ut_assert_true(att.yaw_body - M_PI_2_F < SIGMA_SINGLE_OP);
ut_assert_true(-att.thrust_body[2] - 1.0f < SIGMA_SINGLE_OP);
/* expected: same as before but roll 180
* reason: thrust points straight down and order Euler
* order is: 1. roll, 2. pitch, 3. yaw
*/
thr = matrix::Vector3f(0.0f, 0.0f, 1.0f);
att = ControlMath::thrustToAttitude(thr, yaw);
ut_assert_true(fabsf(att.roll_body) - M_PI_F < SIGMA_SINGLE_OP);
ut_assert_true(fabsf(att.pitch_body) < SIGMA_SINGLE_OP);
ut_assert_true(att.yaw_body - M_PI_2_F < SIGMA_SINGLE_OP);
ut_assert_true(-att.thrust_body[2] - 1.0f < SIGMA_SINGLE_OP);
/* TODO: find a good way to test it */
return true;
}
bool ControlMathTest::testPrioritizeVector()
{
float max = 5.0f;
// v0 already at max
matrix::Vector2f v0(max, 0);
matrix::Vector2f v1(v0(1), -v0(0));
// the static keywork is a workaround for an internal bug of GCC
// "internal compiler error: in trunc_int_for_mode, at explow.c:55"
matrix::Vector2f v_r = ControlMath::constrainXY(v0, v1, max);
ut_assert_true(fabsf(v_r(0)) - max < SIGMA_SINGLE_OP && v_r(0) > 0.0f);
ut_assert_true(fabsf(v_r(1) - 0.0f) < SIGMA_SINGLE_OP);
// v1 exceeds max but v0 is zero
v0.zero();
v_r = ControlMath::constrainXY(v0, v1, max);
ut_assert_true(fabsf(v_r(1)) - max < SIGMA_SINGLE_OP && v_r(1) < 0.0f);
ut_assert_true(fabsf(v_r(0) - 0.0f) < SIGMA_SINGLE_OP);
// v0 and v1 are below max
v0 = matrix::Vector2f(0.5f, 0.5f);
v1(0) = v0(1); v1(1) = -v0(0);
v_r = ControlMath::constrainXY(v0, v1, max);
float diff = matrix::Vector2f(v_r - (v0 + v1)).length();
ut_assert_true(diff < SIGMA_SINGLE_OP);
// v0 and v1 exceed max and are perpendicular
v0 = matrix::Vector2f(4.0f, 0.0f);
v1 = matrix::Vector2f(0.0f, -4.0f);
v_r = ControlMath::constrainXY(v0, v1, max);
ut_assert_true(v_r(0) - v0(0) < SIGMA_SINGLE_OP && v_r(0) > 0.0f);
float remaining = sqrtf(max * max - (v0(0) * v0(0)));
ut_assert_true(fabsf(v_r(1)) - remaining < SIGMA_SINGLE_OP && v_r(1) < SIGMA_SINGLE_OP);
//TODO: add more tests with vectors not perpendicular
return true;
}
bool ControlMathTest::crossSphereLineTest()
{
matrix::Vector3f prev = matrix::Vector3f(0.0f, 0.0f, 0.0f);
matrix::Vector3f curr = matrix::Vector3f(0.0f, 0.0f, 2.0f);
matrix::Vector3f res;
bool retval = false;
/*
* Testing 9 positions (+) around waypoints (o):
*
* Far + + +
*
* Near + + +
* On trajectory --+----o---------+---------o----+--
* prev curr
*
* Expected targets (1, 2, 3):
* Far + + +
*
*
* On trajectory -------1---------2---------3-------
*
*
* Near + + +
* On trajectory -------o---1---------2-----3-------
*
*
* On trajectory --+----o----1----+--------2/3---+--
*/
// on line, near, before previous waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 0.0f, -0.5f), 1.0f, prev, curr, res);
PX4_WARN("result %.2f, %.2f, %.2f", (double)res(0), (double)res(1), (double)res(2));
ut_assert_true(retval);
ut_compare_float("target A 0", res(0), 0.0f, 2);
ut_compare_float("target A 1", res(1), 0.0f, 2);
ut_compare_float("target A 2", res(2), 0.5f, 2);
// on line, near, before target waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 0.0f, 1.0f), 1.0f, prev, curr, res);
PX4_WARN("result %.2f, %.2f, %.2f", (double)res(0), (double)res(1), (double)res(2));
ut_assert_true(retval);
ut_compare_float("target B 0", res(0), 0.0f, 2);
ut_compare_float("target B 1", res(1), 0.0f, 2);
ut_compare_float("target B 2", res(2), 2.0f, 2);
// on line, near, after target waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 0.0f, 2.5f), 1.0f, prev, curr, res);
PX4_WARN("result %.2f, %.2f, %.2f", (double)res(0), (double)res(1), (double)res(2));
ut_assert_true(retval);
ut_compare_float("target C 0", res(0), 0.0f, 2);
ut_compare_float("target C 1", res(1), 0.0f, 2);
ut_compare_float("target C 2", res(2), 2.0f, 2);
// near, before previous waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 0.5f, -0.5f), 1.0f, prev, curr, res);
PX4_WARN("result %.2f, %.2f, %.2f", (double)res(0), (double)res(1), (double)res(2));
ut_assert_true(retval);
ut_compare_float("target D 0", res(0), 0.0f, 2);
ut_compare_float("target D 1", res(1), 0.0f, 2);
ut_compare_float("target D 2", res(2), 0.37f, 2);
// near, before target waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 0.5f, 1.0f), 1.0f, prev, curr, res);
PX4_WARN("result %.2f, %.2f, %.2f", (double)res(0), (double)res(1), (double)res(2));
ut_assert_true(retval);
ut_compare_float("target E 0", res(0), 0.0f, 2);
ut_compare_float("target E 1", res(1), 0.0f, 2);
ut_compare_float("target E 2", res(2), 1.87f, 2);
// near, after target waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 0.5f, 2.5f), 1.0f, prev, curr, res);
PX4_WARN("result %.2f, %.2f, %.2f", (double)res(0), (double)res(1), (double)res(2));
ut_assert_true(retval);
ut_compare_float("target F 0", res(0), 0.0f, 2);
ut_compare_float("target F 1", res(1), 0.0f, 2);
ut_compare_float("target F 2", res(2), 2.0f, 2);
// far, before previous waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 2.0f, -0.5f), 1.0f, prev, curr, res);
PX4_WARN("result %.2f, %.2f, %.2f", (double)res(0), (double)res(1), (double)res(2));
ut_assert_false(retval);
ut_compare_float("target G 0", res(0), 0.0f, 2);
ut_compare_float("target G 1", res(1), 0.0f, 2);
ut_compare_float("target G 2", res(2), 0.0f, 2);
// far, before target waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 2.0f, 1.0f), 1.0f, prev, curr, res);
PX4_WARN("result %.2f, %.2f, %.2f", (double)res(0), (double)res(1), (double)res(2));
ut_assert_false(retval);
ut_compare_float("target H 0", res(0), 0.0f, 2);
ut_compare_float("target H 1", res(1), 0.0f, 2);
ut_compare_float("target H 2", res(2), 1.0f, 2);
// far, after target waypoint
retval = ControlMath::cross_sphere_line(matrix::Vector3f(0.0f, 2.0f, 2.5f), 1.0f, prev, curr, res);
PX4_WARN("result %.2f, %.2f, %.2f", (double)res(0), (double)res(1), (double)res(2));
ut_assert_false(retval);
ut_compare_float("target I 0", res(0), 0.0f, 2);
ut_compare_float("target I 1", res(1), 0.0f, 2);
ut_compare_float("target I 2", res(2), 2.0f, 2);
return true;
}
ut_declare_test_c(test_controlmath, ControlMathTest)

View File

@ -83,7 +83,6 @@ const struct {
{"bezier", test_bezierQuad, 0},
{"bson", test_bson, 0},
{"conv", test_conv, 0},
{"ctlmath", test_controlmath, 0},
{"dataman", test_dataman, OPT_NOJIGTEST | OPT_NOALLTEST},
{"file2", test_file2, OPT_NOJIGTEST},
{"float", test_float, 0},

View File

@ -47,7 +47,6 @@ extern int test_adc(int argc, char *argv[]);
extern int test_autodeclination(int argc, char *argv[]);
extern int test_bezierQuad(int argc, char *argv[]);
extern int test_bson(int argc, char *argv[]);
extern int test_controlmath(int argc, char *argv[]);
extern int test_conv(int argc, char *argv[]);
extern int test_dataman(int argc, char *argv[]);
extern int test_file(int argc, char *argv[]);