Daniel Agar
8 years ago
22 changed files with 210 additions and 388 deletions
@ -0,0 +1,24 @@ |
|||||||
|
/**
|
||||||
|
* @group Testing |
||||||
|
*/ |
||||||
|
PARAM_DEFINE_INT32(TEST_1, 2); |
||||||
|
|
||||||
|
/**
|
||||||
|
* @group Testing |
||||||
|
*/ |
||||||
|
PARAM_DEFINE_INT32(TEST_2, 4); |
||||||
|
|
||||||
|
/**
|
||||||
|
* @group Testing |
||||||
|
*/ |
||||||
|
PARAM_DEFINE_INT32(TEST_RC_X, 8); |
||||||
|
|
||||||
|
/**
|
||||||
|
* @group Testing |
||||||
|
*/ |
||||||
|
PARAM_DEFINE_INT32(TEST_RC2_X, 16); |
||||||
|
|
||||||
|
/**
|
||||||
|
* @group Testing |
||||||
|
*/ |
||||||
|
PARAM_DEFINE_INT32(TEST_PARAMS, 12345678); |
@ -0,0 +1,172 @@ |
|||||||
|
#include <unit_test/unit_test.h> |
||||||
|
|
||||||
|
class ParameterTest : public UnitTest |
||||||
|
{ |
||||||
|
public: |
||||||
|
virtual bool run_tests(); |
||||||
|
|
||||||
|
ParameterTest() |
||||||
|
{ |
||||||
|
p0 = param_find("TEST_RC_X"); |
||||||
|
p1 = param_find("TEST_RC2_X"); |
||||||
|
p2 = param_find("TEST_1"); |
||||||
|
p3 = param_find("TEST_2"); |
||||||
|
} |
||||||
|
|
||||||
|
private: |
||||||
|
|
||||||
|
param_t p0{PARAM_INVALID}; |
||||||
|
param_t p1{PARAM_INVALID}; |
||||||
|
param_t p2{PARAM_INVALID}; |
||||||
|
param_t p3{PARAM_INVALID}; |
||||||
|
|
||||||
|
bool _assert_parameter_int_value(param_t param, int32_t expected); |
||||||
|
bool _set_all_int_parameters_to(int32_t value); |
||||||
|
|
||||||
|
bool SimpleFind(); |
||||||
|
bool ResetAll(); |
||||||
|
bool ResetAllExcludesOne(); |
||||||
|
bool ResetAllExcludesTwo(); |
||||||
|
bool ResetAllExcludesBoundaryCheck(); |
||||||
|
bool ResetAllExcludesWildcard(); |
||||||
|
}; |
||||||
|
|
||||||
|
bool ParameterTest::_assert_parameter_int_value(param_t param, int32_t expected) |
||||||
|
{ |
||||||
|
int32_t value; |
||||||
|
int result = param_get(param, &value); |
||||||
|
ut_compare("param_get did not return parameter", 0, result); |
||||||
|
ut_compare("value for param doesn't match default value", expected, value); |
||||||
|
|
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
bool ParameterTest::_set_all_int_parameters_to(int32_t value) |
||||||
|
{ |
||||||
|
param_set(p0, &value); |
||||||
|
param_set(p1, &value); |
||||||
|
param_set(p2, &value); |
||||||
|
param_set(p3, &value); |
||||||
|
|
||||||
|
bool ret = false; |
||||||
|
|
||||||
|
ret = ret || _assert_parameter_int_value(p0, value); |
||||||
|
ret = ret || _assert_parameter_int_value(p1, value); |
||||||
|
ret = ret || _assert_parameter_int_value(p2, value); |
||||||
|
ret = ret || _assert_parameter_int_value(p3, value); |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
bool ParameterTest::SimpleFind() |
||||||
|
{ |
||||||
|
param_t param = param_find("TEST_2"); |
||||||
|
|
||||||
|
ut_assert_true(PARAM_INVALID != param); |
||||||
|
|
||||||
|
int32_t value; |
||||||
|
int result = param_get(param, &value); |
||||||
|
|
||||||
|
ut_compare("param_get did not return parameter", 0, result); |
||||||
|
ut_compare("value of returned parameter does not match", 4, value); |
||||||
|
|
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
bool ParameterTest::ResetAll() |
||||||
|
{ |
||||||
|
_set_all_int_parameters_to(50); |
||||||
|
|
||||||
|
param_reset_all(); |
||||||
|
|
||||||
|
bool ret = false; |
||||||
|
|
||||||
|
ret = ret || _assert_parameter_int_value(p0, 8); |
||||||
|
ret = ret || _assert_parameter_int_value(p1, 16); |
||||||
|
ret = ret || _assert_parameter_int_value(p2, 2); |
||||||
|
ret = ret || _assert_parameter_int_value(p3, 4); |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
bool ParameterTest::ResetAllExcludesOne() |
||||||
|
{ |
||||||
|
_set_all_int_parameters_to(50); |
||||||
|
|
||||||
|
const char *excludes[] = {"TEST_RC_X"}; |
||||||
|
param_reset_excludes(excludes, 1); |
||||||
|
|
||||||
|
bool ret = false; |
||||||
|
|
||||||
|
ret = ret || _assert_parameter_int_value(p0, 50); |
||||||
|
ret = ret || _assert_parameter_int_value(p1, 16); |
||||||
|
ret = ret || _assert_parameter_int_value(p2, 2); |
||||||
|
ret = ret || _assert_parameter_int_value(p3, 4); |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
bool ParameterTest::ResetAllExcludesTwo() |
||||||
|
{ |
||||||
|
_set_all_int_parameters_to(50); |
||||||
|
|
||||||
|
const char *excludes[] = {"TEST_RC_X", "TEST_1"}; |
||||||
|
param_reset_excludes(excludes, 2); |
||||||
|
|
||||||
|
bool ret = false; |
||||||
|
|
||||||
|
ret = ret || _assert_parameter_int_value(p0, 50); |
||||||
|
ret = ret || _assert_parameter_int_value(p1, 16); |
||||||
|
ret = ret || _assert_parameter_int_value(p2, 50); |
||||||
|
ret = ret || _assert_parameter_int_value(p3, 4); |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
bool ParameterTest::ResetAllExcludesBoundaryCheck() |
||||||
|
{ |
||||||
|
_set_all_int_parameters_to(50); |
||||||
|
|
||||||
|
const char *excludes[] = {"TEST_RC_X", "TEST_1"}; |
||||||
|
param_reset_excludes(excludes, 1); |
||||||
|
|
||||||
|
bool ret = false; |
||||||
|
|
||||||
|
ret = ret || _assert_parameter_int_value(p0, 50); |
||||||
|
ret = ret || _assert_parameter_int_value(p1, 16); |
||||||
|
ret = ret || _assert_parameter_int_value(p2, 2); |
||||||
|
ret = ret || _assert_parameter_int_value(p3, 4); |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
bool ParameterTest::ResetAllExcludesWildcard() |
||||||
|
{ |
||||||
|
_set_all_int_parameters_to(50); |
||||||
|
|
||||||
|
const char *excludes[] = {"TEST_RC*"}; |
||||||
|
param_reset_excludes(excludes, 1); |
||||||
|
|
||||||
|
bool ret = false; |
||||||
|
|
||||||
|
ret = ret || _assert_parameter_int_value(p0, 50); |
||||||
|
ret = ret || _assert_parameter_int_value(p1, 50); |
||||||
|
ret = ret || _assert_parameter_int_value(p2, 2); |
||||||
|
ret = ret || _assert_parameter_int_value(p3, 4); |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
bool ParameterTest::run_tests() |
||||||
|
{ |
||||||
|
ut_run_test(SimpleFind); |
||||||
|
ut_run_test(ResetAll); |
||||||
|
ut_run_test(ResetAllExcludesOne); |
||||||
|
ut_run_test(ResetAllExcludesTwo); |
||||||
|
ut_run_test(ResetAllExcludesBoundaryCheck); |
||||||
|
ut_run_test(ResetAllExcludesWildcard); |
||||||
|
|
||||||
|
return (_tests_failed == 0); |
||||||
|
} |
||||||
|
|
||||||
|
ut_declare_test_c(test_parameters, ParameterTest) |
@ -1,22 +0,0 @@ |
|||||||
./obj/* |
|
||||||
gtest_main.a |
|
||||||
dsm_test |
|
||||||
mixer_test |
|
||||||
sf0x_test |
|
||||||
sbus2_test |
|
||||||
autodeclination_test |
|
||||||
rc_input_test |
|
||||||
conversion_test |
|
||||||
param_test |
|
||||||
*.a |
|
||||||
sample_unittest |
|
||||||
CMakeCache.txt |
|
||||||
CMakeFiles |
|
||||||
CTestTestfile.cmake |
|
||||||
cmake_install.cmake |
|
||||||
Makefile |
|
||||||
.ninja_deps |
|
||||||
.ninja_log |
|
||||||
build.ninja |
|
||||||
rules.ninja |
|
||||||
|
|
@ -1,118 +0,0 @@ |
|||||||
cmake_minimum_required(VERSION 3.1) |
|
||||||
|
|
||||||
if("${CMAKE_C_COMPILER_ID}" MATCHES "Clang") |
|
||||||
add_compile_options(-Qunused-arguments ) |
|
||||||
endif() |
|
||||||
if("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang") |
|
||||||
add_compile_options(-Qunused-arguments) |
|
||||||
endif() |
|
||||||
|
|
||||||
project(px4_unittests) |
|
||||||
enable_testing() |
|
||||||
|
|
||||||
message(STATUS ${CONFIG}) |
|
||||||
|
|
||||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -Werror -std=gnu99 -g") |
|
||||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Werror -std=gnu++0x -g -fno-exceptions -fno-rtti -fno-threadsafe-statics -DCONFIG_WCHAR_BUILTIN -D__CUSTOM_FILE_IO__") |
|
||||||
|
|
||||||
# code coverage |
|
||||||
if ($ENV{PX4_CODE_COVERAGE} MATCHES "1") |
|
||||||
message(STATUS "Code coverage build flags enabled") |
|
||||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -O0 -g3 -fprofile-arcs -ftest-coverage --coverage") |
|
||||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O0 -g3 -fprofile-arcs -ftest-coverage --coverage") |
|
||||||
endif() |
|
||||||
|
|
||||||
if (NOT PX4_SOURCE_DIR) |
|
||||||
set(PX4_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}/..") |
|
||||||
endif() |
|
||||||
|
|
||||||
set(GTEST_DIR ${PX4_SOURCE_DIR}/unittests/googletest) |
|
||||||
add_subdirectory(${GTEST_DIR}) |
|
||||||
include_directories(${GTEST_DIR}/include) |
|
||||||
|
|
||||||
set(PX4_SRC ${PX4_SOURCE_DIR}/src) |
|
||||||
set(PX4_SITL_BUILD ${PX4_SRC}/../build_posix_sitl_default) |
|
||||||
|
|
||||||
include_directories(${PX4_SOURCE_DIR}) |
|
||||||
include_directories(${PX4_SITL_BUILD}/src) |
|
||||||
include_directories(${PX4_SITL_BUILD}/src/modules) |
|
||||||
include_directories(${PX4_SITL_BUILD}/src/modules/param) |
|
||||||
include_directories(${PX4_SITL_BUILD}/src/modules/uORB) |
|
||||||
include_directories(${PX4_SRC}) |
|
||||||
include_directories(${PX4_SRC}/drivers) |
|
||||||
include_directories(${PX4_SRC}/drivers/device) |
|
||||||
include_directories(${PX4_SRC}/lib) |
|
||||||
include_directories(${PX4_SRC}/lib/DriverFramework/framework/include) |
|
||||||
include_directories(${PX4_SRC}/modules) |
|
||||||
include_directories(${PX4_SRC}/include) |
|
||||||
include_directories(${PX4_SRC}/modules/uORB) |
|
||||||
include_directories(${PX4_SRC}/platforms) |
|
||||||
include_directories(${PX4_SRC}/platforms/posix/include) |
|
||||||
include_directories(${PX4_SRC}/platforms/posix/px4_layer) |
|
||||||
include_directories(${PX4_SRC}/platforms/posix/work_queue) |
|
||||||
|
|
||||||
add_definitions(-D__CUSTOM_FILE_IO__) |
|
||||||
add_definitions(-D__EXPORT=) |
|
||||||
add_definitions(-D__PX4_POSIX) |
|
||||||
add_definitions(-D__PX4_TESTS) |
|
||||||
add_definitions(-D__PX4_UNIT_TESTS) |
|
||||||
add_definitions(-D_UNIT_TEST=) |
|
||||||
add_definitions(-DPARAM_NO_AUTOSAVE) |
|
||||||
add_definitions(-DERROR=-1) |
|
||||||
add_definitions(-Dmain_t=int) |
|
||||||
add_definitions(-Dnoreturn_function=) |
|
||||||
add_definitions(-DOK=0) |
|
||||||
|
|
||||||
if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin") |
|
||||||
add_definitions(-D__PX4_DARWIN) |
|
||||||
else() |
|
||||||
add_definitions(-D__PX4_LINUX) |
|
||||||
endif() |
|
||||||
|
|
||||||
# the following flags only apply to the PX4 source |
|
||||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -include visibility.h") |
|
||||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -include visibility.h") |
|
||||||
|
|
||||||
set(PX4_PLATFORM |
|
||||||
${PX4_SITL_BUILD}/libmsg_gen.a |
|
||||||
${PX4_SITL_BUILD}/src/drivers/boards/sitl/libdrivers__boards__sitl.a |
|
||||||
${PX4_SITL_BUILD}/src/drivers/device/libdrivers__device.a |
|
||||||
${PX4_SITL_BUILD}/src/lib/DriverFramework/framework/liblib__DriverFramework__framework.a |
|
||||||
${PX4_SITL_BUILD}/src/lib/DriverFramework/framework/src/libdf_driver_framework.a |
|
||||||
${PX4_SITL_BUILD}/src/platforms/common/libplatforms__common.a |
|
||||||
${PX4_SITL_BUILD}/src/platforms/posix/px4_layer/libplatforms__posix__px4_layer.a |
|
||||||
${PX4_SITL_BUILD}/src/platforms/posix/work_queue/libplatforms__posix__work_queue.a |
|
||||||
) |
|
||||||
|
|
||||||
# check |
|
||||||
add_custom_target(check |
|
||||||
COMMAND ${CMAKE_CTEST_COMMAND} -j2 --output-on-failure |
|
||||||
WORKING_DIR ${PX4_BINARY_DIR} |
|
||||||
USES_TERMINAL) |
|
||||||
|
|
||||||
# add_gtest |
|
||||||
function(add_gtest) |
|
||||||
foreach(test_name ${ARGN}) |
|
||||||
if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin") |
|
||||||
target_link_libraries(${test_name} gtest_main pthread ${PX4_PLATFORM}) |
|
||||||
else() |
|
||||||
target_link_libraries(${test_name} gtest_main pthread rt ${PX4_PLATFORM}) |
|
||||||
endif() |
|
||||||
add_test(NAME ${test_name} COMMAND ${test_name} --gtest_output=xml WORKING_DIRECTORY ${PX4_BINARY_DIR}) |
|
||||||
add_dependencies(check ${test_name}) |
|
||||||
endforeach() |
|
||||||
endfunction() |
|
||||||
|
|
||||||
|
|
||||||
####################################################################### |
|
||||||
# TESTS |
|
||||||
####################################################################### |
|
||||||
# add_executable(example_test example_test.cpp) |
|
||||||
# add_gtest(example_test) |
|
||||||
|
|
||||||
# param_test |
|
||||||
add_executable(param_test setup.cpp param_test.cpp uorb_stub.cpp |
|
||||||
${PX4_SRC}/modules/systemlib/bson/tinybson.c |
|
||||||
${PX4_SRC}/modules/systemlib/param/param.c) |
|
||||||
target_link_libraries(param_test ${PX4_PLATFORM}) |
|
||||||
add_gtest(param_test) |
|
@ -1,153 +0,0 @@ |
|||||||
#include <systemlib/param/param.h> |
|
||||||
|
|
||||||
#include "gtest/gtest.h" |
|
||||||
|
|
||||||
/*
|
|
||||||
* These will be used in param.c if compiling for unit tests |
|
||||||
*/ |
|
||||||
struct param_info_s param_array[256]; |
|
||||||
struct param_info_s *param_info_base; |
|
||||||
struct param_info_s *param_info_limit; |
|
||||||
|
|
||||||
/*
|
|
||||||
* Adds test parameters |
|
||||||
*/ |
|
||||||
void _add_parameters() |
|
||||||
{ |
|
||||||
struct param_info_s test_1 = { |
|
||||||
"TEST_1", |
|
||||||
PARAM_TYPE_INT32 |
|
||||||
}; |
|
||||||
test_1.val.i = 2; |
|
||||||
|
|
||||||
struct param_info_s test_2 = { |
|
||||||
"TEST_2", |
|
||||||
PARAM_TYPE_INT32 |
|
||||||
}; |
|
||||||
test_2.val.i = 4; |
|
||||||
|
|
||||||
struct param_info_s rc_x = { |
|
||||||
"RC_X", |
|
||||||
PARAM_TYPE_INT32 |
|
||||||
}; |
|
||||||
rc_x.val.i = 8; |
|
||||||
|
|
||||||
struct param_info_s rc2_x = { |
|
||||||
"RC2_X", |
|
||||||
PARAM_TYPE_INT32 |
|
||||||
}; |
|
||||||
rc2_x.val.i = 16; |
|
||||||
|
|
||||||
param_array[0] = rc_x; |
|
||||||
param_array[1] = rc2_x; |
|
||||||
param_array[2] = test_1; |
|
||||||
param_array[3] = test_2; |
|
||||||
param_info_base = (struct param_info_s *) ¶m_array[0]; |
|
||||||
// needs to point at the end of the data,
|
|
||||||
// therefore number of params + 1
|
|
||||||
param_info_limit = (struct param_info_s *) ¶m_array[4]; |
|
||||||
|
|
||||||
} |
|
||||||
|
|
||||||
void _assert_parameter_int_value(param_t param, int32_t expected) |
|
||||||
{ |
|
||||||
int32_t value; |
|
||||||
int result = param_get(param, &value); |
|
||||||
ASSERT_EQ(0, result) << printf("param_get (%i) did not return parameter\n", (int)param); |
|
||||||
ASSERT_EQ(expected, value) << printf("value for param (%i) doesn't match default value\n", (int)param); |
|
||||||
} |
|
||||||
|
|
||||||
void _set_all_int_parameters_to(int32_t value) |
|
||||||
{ |
|
||||||
param_set((param_t)0, &value); |
|
||||||
param_set((param_t)1, &value); |
|
||||||
param_set((param_t)2, &value); |
|
||||||
param_set((param_t)3, &value); |
|
||||||
|
|
||||||
_assert_parameter_int_value((param_t)0, value); |
|
||||||
_assert_parameter_int_value((param_t)1, value); |
|
||||||
_assert_parameter_int_value((param_t)2, value); |
|
||||||
_assert_parameter_int_value((param_t)3, value); |
|
||||||
} |
|
||||||
|
|
||||||
TEST(ParamTest, SimpleFind) |
|
||||||
{ |
|
||||||
_add_parameters(); |
|
||||||
|
|
||||||
param_t param = param_find("TEST_2"); |
|
||||||
ASSERT_NE(PARAM_INVALID, param) << "param_find did not find parameter"; |
|
||||||
|
|
||||||
int32_t value; |
|
||||||
int result = param_get(param, &value); |
|
||||||
ASSERT_EQ(0, result) << "param_get did not return parameter"; |
|
||||||
ASSERT_EQ(4, value) << "value of returned parameter does not match"; |
|
||||||
} |
|
||||||
|
|
||||||
TEST(ParamTest, ResetAll) |
|
||||||
{ |
|
||||||
_add_parameters(); |
|
||||||
_set_all_int_parameters_to(50); |
|
||||||
|
|
||||||
param_reset_all(); |
|
||||||
|
|
||||||
_assert_parameter_int_value((param_t)0, 8); |
|
||||||
_assert_parameter_int_value((param_t)1, 16); |
|
||||||
_assert_parameter_int_value((param_t)2, 2); |
|
||||||
_assert_parameter_int_value((param_t)3, 4); |
|
||||||
} |
|
||||||
|
|
||||||
TEST(ParamTest, ResetAllExcludesOne) |
|
||||||
{ |
|
||||||
_add_parameters(); |
|
||||||
_set_all_int_parameters_to(50); |
|
||||||
|
|
||||||
const char *excludes[] = {"RC_X"}; |
|
||||||
param_reset_excludes(excludes, 1); |
|
||||||
|
|
||||||
_assert_parameter_int_value((param_t)0, 50); |
|
||||||
_assert_parameter_int_value((param_t)1, 16); |
|
||||||
_assert_parameter_int_value((param_t)2, 2); |
|
||||||
_assert_parameter_int_value((param_t)3, 4); |
|
||||||
} |
|
||||||
|
|
||||||
TEST(ParamTest, ResetAllExcludesTwo) |
|
||||||
{ |
|
||||||
_add_parameters(); |
|
||||||
_set_all_int_parameters_to(50); |
|
||||||
|
|
||||||
const char *excludes[] = {"RC_X", "TEST_1"}; |
|
||||||
param_reset_excludes(excludes, 2); |
|
||||||
|
|
||||||
_assert_parameter_int_value((param_t)0, 50); |
|
||||||
_assert_parameter_int_value((param_t)1, 16); |
|
||||||
_assert_parameter_int_value((param_t)2, 50); |
|
||||||
_assert_parameter_int_value((param_t)3, 4); |
|
||||||
} |
|
||||||
|
|
||||||
TEST(ParamTest, ResetAllExcludesBoundaryCheck) |
|
||||||
{ |
|
||||||
_add_parameters(); |
|
||||||
_set_all_int_parameters_to(50); |
|
||||||
|
|
||||||
const char *excludes[] = {"RC_X", "TEST_1"}; |
|
||||||
param_reset_excludes(excludes, 1); |
|
||||||
|
|
||||||
_assert_parameter_int_value((param_t)0, 50); |
|
||||||
_assert_parameter_int_value((param_t)1, 16); |
|
||||||
_assert_parameter_int_value((param_t)2, 2); |
|
||||||
_assert_parameter_int_value((param_t)3, 4); |
|
||||||
} |
|
||||||
|
|
||||||
TEST(ParamTest, ResetAllExcludesWildcard) |
|
||||||
{ |
|
||||||
_add_parameters(); |
|
||||||
_set_all_int_parameters_to(50); |
|
||||||
|
|
||||||
const char *excludes[] = {"RC*"}; |
|
||||||
param_reset_excludes(excludes, 1); |
|
||||||
|
|
||||||
_assert_parameter_int_value((param_t)0, 50); |
|
||||||
_assert_parameter_int_value((param_t)1, 50); |
|
||||||
_assert_parameter_int_value((param_t)2, 2); |
|
||||||
_assert_parameter_int_value((param_t)3, 4); |
|
||||||
} |
|
@ -1,23 +0,0 @@ |
|||||||
#include <systemlib/param/param.h> |
|
||||||
|
|
||||||
#include "gtest/gtest.h" |
|
||||||
|
|
||||||
|
|
||||||
class TestEnvironment: public ::testing::Environment { |
|
||||||
public: |
|
||||||
/**
|
|
||||||
* Testing setup: this is called before the actual tests are executed. |
|
||||||
*/ |
|
||||||
virtual void SetUp() |
|
||||||
{ |
|
||||||
param_init(); |
|
||||||
} |
|
||||||
}; |
|
||||||
|
|
||||||
int main(int argc, char* argv[]) |
|
||||||
{ |
|
||||||
::testing::InitGoogleTest(&argc, argv); |
|
||||||
// gtest takes ownership of the TestEnvironment ptr - we don't delete it.
|
|
||||||
::testing::AddGlobalTestEnvironment(new TestEnvironment); |
|
||||||
return RUN_ALL_TESTS(); |
|
||||||
} |
|
@ -1,26 +0,0 @@ |
|||||||
#include <stdint.h> |
|
||||||
#include <sys/types.h> |
|
||||||
//#include "gmock/gmock.h"
|
|
||||||
|
|
||||||
#include "uORB/uORB.h" |
|
||||||
|
|
||||||
/******************************************
|
|
||||||
* uORB stubs (incomplete) |
|
||||||
* |
|
||||||
* TODO: use googlemock |
|
||||||
******************************************/ |
|
||||||
|
|
||||||
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data) |
|
||||||
{ |
|
||||||
return (orb_advert_t)0; |
|
||||||
} |
|
||||||
|
|
||||||
orb_advert_t orb_advertise_queue(const struct orb_metadata *meta, const void *data, unsigned int queue_size) |
|
||||||
{ |
|
||||||
return (orb_advert_t)0; |
|
||||||
} |
|
||||||
|
|
||||||
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) |
|
||||||
{ |
|
||||||
return 0; |
|
||||||
} |
|
Loading…
Reference in new issue