Browse Source
* Add kdevelop to gitignore * Add test stubs * Rename px4_add_gtest to px4_add_unit_gtest * Add infrastructure to run functional tests * Add example tests with parameters and uorb messages * Fix memory issues in destructors in uORB manager and CDev * Add a more real-world test of the collision preventionsbg
Julian Kent
6 years ago
committed by
GitHub
28 changed files with 535 additions and 16 deletions
@ -0,0 +1,54 @@
@@ -0,0 +1,54 @@
|
||||
#!/usr/bin/env python |
||||
|
||||
from sys import argv, stderr |
||||
from subprocess import call, check_output |
||||
|
||||
|
||||
def list_all_tests(bin_path): |
||||
out = check_output(['./' + bin_path,"--gtest_list_tests"]) |
||||
out = out.split("\n") |
||||
if len(out) > 1: |
||||
prefix = '' |
||||
tests_list = [] |
||||
for token in out: |
||||
if len(token) == 0: |
||||
continue |
||||
if token[-1] == '.': |
||||
prefix = token |
||||
continue |
||||
if token[0] == ' ' and token[1] == ' ' and len(token) > 0: |
||||
tests_list.append(''.join([prefix, token[2:]])) |
||||
continue |
||||
|
||||
return tests_list |
||||
|
||||
else: |
||||
return [] |
||||
|
||||
|
||||
|
||||
def run_tests(bin_path, tests_list, args): |
||||
for test in tests_list: |
||||
call_args = ['./' + bin_path, ' '.join(args), '--gtest_filter=*{}'.format(test)] |
||||
print(' '.join(call_args)) |
||||
result = call(call_args) |
||||
if result != 0: |
||||
return result |
||||
return 0 |
||||
|
||||
|
||||
|
||||
def main(): |
||||
if len(argv) >= 2: |
||||
try: |
||||
exit(run_tests(argv[1], list_all_tests(argv[1]), argv[2:])) |
||||
except: |
||||
print('Error with arguments "' + ' '.join(argv[1:]) + '"') |
||||
raise |
||||
print('Runs each gtest test in a difference process') |
||||
print('Usage: ' + argv[0] + ' path/to/gtest.bin [GTEST_OPTIONS]') |
||||
exit(1) |
||||
|
||||
|
||||
if __name__ == '__main__': |
||||
main() |
@ -0,0 +1,135 @@
@@ -0,0 +1,135 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 <CollisionPrevention/CollisionPrevention.hpp> |
||||
|
||||
// to run: make tests TESTFILTER=CollisionPrevention
|
||||
|
||||
class CollisionPreventionTest : public ::testing::Test |
||||
{ |
||||
public: |
||||
void SetUp() override |
||||
{ |
||||
uORB::Manager::initialize(); |
||||
param_init(); |
||||
} |
||||
|
||||
void TearDown() override |
||||
{ |
||||
param_reset_all(); |
||||
uORB::Manager::terminate(); |
||||
} |
||||
}; |
||||
|
||||
TEST_F(CollisionPreventionTest, instantiation) { CollisionPrevention cp(nullptr); } |
||||
|
||||
TEST_F(CollisionPreventionTest, behaviorOff) |
||||
{ |
||||
// GIVEN: a simple setup condition
|
||||
CollisionPrevention cp(nullptr); |
||||
matrix::Vector2f original_setpoint(10, 0); |
||||
float max_speed = 3.f; |
||||
matrix::Vector2f curr_pos(0, 0); |
||||
matrix::Vector2f curr_vel(2, 0); |
||||
|
||||
// WHEN: we check if the setpoint should be modified
|
||||
matrix::Vector2f modified_setpoint = original_setpoint; |
||||
cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); |
||||
|
||||
// THEN: it should be the same
|
||||
EXPECT_EQ(original_setpoint, modified_setpoint); |
||||
} |
||||
|
||||
TEST_F(CollisionPreventionTest, withoutObstacleMessageNothing) |
||||
{ |
||||
// GIVEN: a simple setup condition
|
||||
CollisionPrevention cp(nullptr); |
||||
matrix::Vector2f original_setpoint(10, 0); |
||||
float max_speed = 3.f; |
||||
matrix::Vector2f curr_pos(0, 0); |
||||
matrix::Vector2f curr_vel(2, 0); |
||||
|
||||
// AND: a parameter handle
|
||||
param_t param = param_handle(px4::params::MPC_COL_PREV_D); |
||||
|
||||
|
||||
// WHEN: we set the parameter check then apply the setpoint modification
|
||||
float value = 10; // try to keep 10m away from obstacles
|
||||
param_set(param, &value); |
||||
|
||||
matrix::Vector2f modified_setpoint = original_setpoint; |
||||
cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); |
||||
|
||||
// THEN: it shouldn't interfere with the setpoint, because there isn't an obstacle
|
||||
EXPECT_EQ(original_setpoint, modified_setpoint); |
||||
} |
||||
|
||||
TEST_F(CollisionPreventionTest, testBehaviorOnWithAnObstacle) |
||||
{ |
||||
// GIVEN: a simple setup condition
|
||||
CollisionPrevention cp(nullptr); |
||||
matrix::Vector2f original_setpoint(10, 0); |
||||
float max_speed = 3; |
||||
matrix::Vector2f curr_pos(0, 0); |
||||
matrix::Vector2f curr_vel(2, 0); |
||||
|
||||
// AND: a parameter handle
|
||||
param_t param = param_handle(px4::params::MPC_COL_PREV_D); |
||||
float value = 10; // try to keep 10m distance
|
||||
param_set(param, &value); |
||||
|
||||
// AND: an obstacle message
|
||||
obstacle_distance_s message; |
||||
memset(&message, 0xDEAD, sizeof(message)); |
||||
message.min_distance = 100; |
||||
message.max_distance = 1000; |
||||
message.timestamp = hrt_absolute_time(); |
||||
int distances_array_size = sizeof(message.distances) / sizeof(message.distances[0]); |
||||
message.increment = 360 / distances_array_size; |
||||
|
||||
for (int i = 0; i < distances_array_size; i++) { |
||||
message.distances[i] = 101; |
||||
} |
||||
|
||||
orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &message); |
||||
|
||||
|
||||
// WHEN: we publish the message and set the parameter and then run the setpoint modification
|
||||
matrix::Vector2f modified_setpoint = original_setpoint; |
||||
cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); |
||||
orb_unadvertise(obstacle_distance_pub); |
||||
|
||||
// THEN: it should be cut down a lot
|
||||
EXPECT_GT(original_setpoint.norm() * 0.5f, modified_setpoint.norm()); //FIXME: this should actually be constrained to 0
|
||||
} |
@ -0,0 +1,114 @@
@@ -0,0 +1,114 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 <px4_module_params.h> |
||||
#include <uORB/Subscription.hpp> |
||||
#include <uORB/topics/obstacle_distance.h> |
||||
#include <uORB/uORBManager.hpp> |
||||
|
||||
#include <gtest/gtest.h> |
||||
|
||||
class ParameterTest : public ::testing::Test |
||||
{ |
||||
public: |
||||
void SetUp() override |
||||
{ |
||||
uORB::Manager::initialize(); |
||||
param_init(); |
||||
} |
||||
|
||||
void TearDown() override |
||||
{ |
||||
param_reset_all(); |
||||
uORB::Manager::terminate(); |
||||
} |
||||
}; |
||||
|
||||
|
||||
TEST_F(ParameterTest, testParamReadWrite) |
||||
{ |
||||
// GIVEN a parameter handle
|
||||
param_t param = param_handle(px4::params::MPC_COL_PREV_D); |
||||
|
||||
// WHEN: we get the parameter
|
||||
float value = -999.f; |
||||
int status = param_get(param, &value); |
||||
|
||||
// THEN it should be successful and have the default value
|
||||
EXPECT_EQ(0, status); |
||||
EXPECT_EQ(-1, value); |
||||
|
||||
// WHEN: we set the parameter
|
||||
value = 42.f; |
||||
status = param_set(param, &value); |
||||
|
||||
// THEN: it should be successful
|
||||
EXPECT_EQ(0, status); |
||||
|
||||
// WHEN: we get the parameter again
|
||||
float value2 = -1999.f; |
||||
status = param_get(param, &value2); |
||||
|
||||
// THEN: it should be exactly the value we set
|
||||
EXPECT_EQ(0, status); |
||||
EXPECT_EQ(42.f, value2); |
||||
} |
||||
|
||||
|
||||
TEST_F(ParameterTest, testUorbSendReceive) |
||||
{ |
||||
// GIVEN: a uOrb message
|
||||
obstacle_distance_s message; |
||||
memset(&message, 0xDEAD, sizeof(message)); |
||||
message.min_distance = 1.f; |
||||
message.max_distance = 10.f; |
||||
|
||||
// AND: a subscriber
|
||||
uORB::SubscriptionData<obstacle_distance_s> sub_obstacle_distance{ORB_ID(obstacle_distance)}; |
||||
|
||||
// WHEN we send the message
|
||||
orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &message); |
||||
ASSERT_TRUE(obstacle_distance_pub != nullptr); |
||||
|
||||
// THEN: the subscriber should receive the message
|
||||
sub_obstacle_distance.update(); |
||||
const obstacle_distance_s &obstacle_distance = sub_obstacle_distance.get(); |
||||
|
||||
// AND: the values we got should be the same
|
||||
EXPECT_EQ(message.timestamp, obstacle_distance.timestamp); |
||||
EXPECT_EQ(message.min_distance, obstacle_distance.min_distance); |
||||
EXPECT_EQ(message.max_distance, obstacle_distance.max_distance); |
||||
|
||||
// AND: all the bytes should be equal
|
||||
EXPECT_EQ(0, memcmp(&message, &obstacle_distance, sizeof(message))); |
||||
} |
@ -0,0 +1,41 @@
@@ -0,0 +1,41 @@
|
||||
############################################################################ |
||||
# |
||||
# 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. |
||||
# |
||||
############################################################################ |
||||
|
||||
set(SRCS |
||||
stub_daemon.cpp |
||||
stub_devmgr.cpp |
||||
stub_parameter.cpp |
||||
) |
||||
|
||||
px4_add_library(test_stubs ${SRCS}) |
||||
message("-- ADDING TEST STUBS") |
@ -0,0 +1,6 @@
@@ -0,0 +1,6 @@
|
||||
#include "stub_daemon.h" |
||||
|
||||
|
||||
void init_app_map(apps_map_type &apps) {stub_init_app_map_callback(apps);} |
||||
|
||||
void list_builtins(apps_map_type &apps) {stub_list_builtins_callback(apps);} |
@ -0,0 +1,8 @@
@@ -0,0 +1,8 @@
|
||||
#pragma once |
||||
|
||||
#include <platforms/posix/apps.h> |
||||
|
||||
#include <functional> |
||||
|
||||
std::function<void(apps_map_type &apps)> stub_init_app_map_callback = [](apps_map_type &) {}; |
||||
std::function<void(apps_map_type &apps)> stub_list_builtins_callback = [](apps_map_type &) {}; |
@ -0,0 +1,10 @@
@@ -0,0 +1,10 @@
|
||||
#include "stub_devmgr.h" |
||||
|
||||
|
||||
namespace DriverFramework |
||||
{ |
||||
int DevMgr::getNextDeviceName(unsigned int &index, const char **instancename) |
||||
{ |
||||
return stub_getNextDeviceName_callback(index, instancename); |
||||
} |
||||
} |
@ -0,0 +1,8 @@
@@ -0,0 +1,8 @@
|
||||
#pragma once |
||||
|
||||
#include "DevMgr.hpp" |
||||
|
||||
#include <functional> |
||||
|
||||
std::function<int(unsigned int &, const char **)> stub_getNextDeviceName_callback = [](unsigned int &, |
||||
const char **) {return 0;}; |
@ -0,0 +1,11 @@
@@ -0,0 +1,11 @@
|
||||
#include "stub_parameter.h" |
||||
|
||||
|
||||
|
||||
extern "C" { |
||||
/* This function blocks forever in tests, so override it with a version that can be customized */ |
||||
int pthread_cond_wait(pthread_cond_t *cond, pthread_mutex_t *mutex) |
||||
{ |
||||
return stub_pthread_cond_wait_callback(cond, mutex); |
||||
} |
||||
} |
Loading…
Reference in new issue