Skip to content

Commit

Permalink
Add ntest to build
Browse files Browse the repository at this point in the history
This adds the ntest systemcmd using ntestlib to the build. This is the
equivalent of gtest testing on Posix for NuttX.

This works as follows:
1. At cmake configure time all tests are added to global cmake lists.
2. Then when ntest is configured (last), the collected test sources and
   dependencies are added to the ntest build.

When compiling for NuttX we need to include ntestlib.h, when building
for Posix we need to include gtest.h (see px4_unittesting.h).
  • Loading branch information
julianoes committed Jul 2, 2019
1 parent b967b07 commit be8d4e4
Show file tree
Hide file tree
Showing 12 changed files with 100 additions and 23 deletions.
3 changes: 2 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -425,9 +425,10 @@ endif()
# enable test filtering to run only specific tests with the ctest -R regex functionality
set(TESTFILTER "" CACHE STRING "Filter string for ctest to selectively only run specific tests (ctest -R)")

# if testing is enabled download and configure gtest
list(APPEND CMAKE_MODULE_PATH ${PX4_SOURCE_DIR}/cmake/gtest/)
include(px4_add_gtest)

# if testing is enabled download and configure gtest
if(BUILD_TESTING)
include(gtest)
endif()
Expand Down
1 change: 1 addition & 0 deletions boards/px4/fmu-v2/test.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,7 @@ px4_add_board(
#topic_listener
tune_control
ver
ntest # needs to be last

EXAMPLES
#bottle_drop # OBC challenge
Expand Down
1 change: 1 addition & 0 deletions boards/px4/fmu-v3/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,7 @@ px4_add_board(
tune_control
usb_connected
ver
ntest # needs to be last

EXAMPLES
bottle_drop # OBC challenge
Expand Down
1 change: 1 addition & 0 deletions boards/px4/fmu-v4/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,7 @@ px4_add_board(
tune_control
usb_connected
ver
ntest # needs to be last

EXAMPLES
bottle_drop # OBC challenge
Expand Down
1 change: 1 addition & 0 deletions boards/px4/fmu-v5/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,7 @@ px4_add_board(
tune_control
usb_connected
ver
ntest # needs to be last

EXAMPLES
bottle_drop # OBC challenge
Expand Down
45 changes: 30 additions & 15 deletions cmake/gtest/px4_add_gtest.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -40,31 +40,46 @@ include(px4_base)
# Adds a googletest unit test to the test_results target.
#
function(px4_add_gtest)
# skip if unit testing is not configured
if(BUILD_TESTING)
# parse source file and library dependencies from arguments
px4_parse_function_args(
NAME px4_add_gtest
ONE_VALUE SRC
MULTI_VALUE LINKLIBS
REQUIRED SRC
ARGN ${ARGN})
# parse source file and library dependencies from arguments
px4_parse_function_args(
NAME px4_add_gtest
ONE_VALUE SRC
MULTI_VALUE LINKLIBS
REQUIRED SRC
ARGN ${ARGN})

# infer test name from source filname
get_filename_component(TESTNAME ${SRC} NAME_WE)
string(REPLACE Test "" TESTNAME ${TESTNAME})
set(TESTNAME unit-${TESTNAME})
# infer test name from source filname
get_filename_component(TESTNAME ${SRC} NAME_WE)
string(REPLACE Test "" TESTNAME ${TESTNAME})

if (${PX4_PLATFORM} STREQUAL "nuttx")
get_property(sources GLOBAL PROPERTY ntest_test_sources)
list(APPEND sources ${CMAKE_CURRENT_SOURCE_DIR}/${SRC})
set_property(GLOBAL PROPERTY ntest_test_sources ${sources})

get_property(dependencies GLOBAL PROPERTY ntest_test_dependencies)

foreach(dep ${dependencies})
list(APPEND dependencies ${dep})
endforeach()
set_property(GLOBAL PROPERTY ntest_test_dependencies ${dependencies})

# Note: If the systemcmd ntest is not build, these properties won't be
# taken into account.

else()
set(TESTNAME unit-${TESTNAME})
# build a binary for the unit test
add_executable(${TESTNAME} EXCLUDE_FROM_ALL ${SRC})

# attach it to the unit test target
add_dependencies(test_results ${TESTNAME})

# link the libary to test and gtest
target_link_libraries(${TESTNAME} ${LINKLIBS} gtest_main)

# add the test to the ctest plan
add_test(NAME ${TESTNAME} COMMAND ${TESTNAME})

# attach it to the unit test target
add_dependencies(test_results ${TESTNAME})
endif()
endfunction()
10 changes: 9 additions & 1 deletion platforms/nuttx/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,15 @@ target_link_libraries(px4 PRIVATE
gcc
)

target_link_libraries(px4 PRIVATE ${module_libraries})
foreach(module ${module_libraries})
# Hack for ntest to avoid the linker from stripping the static global test registrars.
if ("${module}" STREQUAL "ntest")
target_link_libraries(px4 PRIVATE -Wl,--whole-archive ${module} -Wl,--no-whole-archive)
message(STATUS "Adding ntest")
else()
target_link_libraries(px4 PRIVATE ${module})
endif()
endforeach()

if (config_romfs_root)
add_subdirectory(${PX4_SOURCE_DIR}/ROMFS ${PX4_BINARY_DIR}/ROMFS)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include <lockstep_scheduler/lockstep_scheduler.h>
#include <gtest/gtest.h>
#include <px4_unittesting.h>
#include <thread>
#include <atomic>
#include <random>
Expand Down
2 changes: 1 addition & 1 deletion src/lib/hysteresis/HysteresisTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
* Tests for system timing hysteresis.
*/

#include <gtest/gtest.h>
#include <px4_unittesting.h>

#include "hysteresis.h"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,9 @@
*
****************************************************************************/

#include <gtest/gtest.h>
#include <AttitudeControl.hpp>
#include <px4_unittesting.h>

#include "AttitudeControl.hpp"

using namespace matrix;

Expand Down
5 changes: 3 additions & 2 deletions src/modules/mc_pos_control/Takeoff/TakeoffTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,9 @@
*
****************************************************************************/

#include <gtest/gtest.h>
#include <Takeoff.hpp>
#include <px4_unittesting.h>

#include "Takeoff.hpp"

TEST(TakeoffTest, Initialization)
{
Expand Down
47 changes: 47 additions & 0 deletions src/platforms/px4_unittesting.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/

/**
* @file px4_unittesting.h
*
* File to include the appropriate header files for unit testing on the
* respective platform.
*/

#pragma once

#ifdef __PX4_NUTTX
#include <lib/ntestlib/ntestlib.h>
#else
#include <gtest/gtest.h>
#endif

0 comments on commit be8d4e4

Please sign in to comment.