Skip to content

Commit

Permalink
restored the testing pipeline from history
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Feb 1, 2024
1 parent bd51f75 commit b27bc2e
Show file tree
Hide file tree
Showing 21 changed files with 289 additions and 436 deletions.
10 changes: 7 additions & 3 deletions ros_packages/mrs_uav_gazebo_simulation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ set(CATKIN_DEPENDENCIES
px4
rospy
std_msgs
mrs_uav_testing
)

find_package(catkin REQUIRED COMPONENTS
Expand All @@ -32,15 +33,18 @@ include_directories(
${mavros_msgs_INCLUDE_DIRS}
)

if(COVERAGE)
message(WARNING "building with --coverage, the performance might be limited")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} --coverage")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} --coverage")
endif()

## --------------------------------------------------------------
## | Testing |
## --------------------------------------------------------------

if(CATKIN_ENABLE_TESTING)

set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} --coverage")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} --coverage")

add_subdirectory(test)

endif()
Expand Down
1 change: 1 addition & 0 deletions ros_packages/mrs_uav_gazebo_simulation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<depend>px4</depend>
<depend>rospy</depend>
<depend>std_msgs</depend>
<depend>mrs_uav_testing</depend>

<depend>python3-jinja2</depend>

Expand Down
24 changes: 1 addition & 23 deletions ros_packages/mrs_uav_gazebo_simulation/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,25 +1,3 @@
find_package(rostest REQUIRED)

### WARNING
### NEVER name your test build unit the same as the folder that it is placed in!
### e.g., this will cause problems:
### add_rostest_gtest(my_test
### my_test/basic.test
### my_test/test.cpp
### )

# basic test

add_rostest_gtest(test_basic
basic/basic.test
basic/test.cpp
)

target_link_libraries(test_basic
${catkin_LIBRARIES}
)

add_dependencies(test_basic
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)
add_subdirectory(takeoff)
43 changes: 21 additions & 22 deletions ros_packages/mrs_uav_gazebo_simulation/test/all_tests.sh
Original file line number Diff line number Diff line change
Expand Up @@ -5,31 +5,30 @@ set -e
trap 'last_command=$current_command; current_command=$BASH_COMMAND' DEBUG
trap 'echo "$0: \"${last_command}\" command failed with exit code $?"' ERR

PACKAGE="mrs_uav_gazebo_simulation"
VERBOSE=1

[ "$VERBOSE" = "0" ] && TEXT_OUTPUT=""
[ "$VERBOSE" = "1" ] && TEXT_OUTPUT="-t"

# build the package
catkin build $PACKAGE # it has to be fully built normally before building with --catkin-make-args tests
catkin build $PACKAGE --no-deps --catkin-make-args tests

TEST_FILES=$(find . -name "*.test" -type f -printf "%f\n")
ORIGINAL_PATH=`pwd`

while [ ! -e ".catkin_tools" ]; do
cd ..
if [[ `pwd` == "/" ]]; then
# we reached the root and didn't find the build/COLCON_IGNORE file - that's a fail!
echo "$0: could not find the root of the current workspace".
return 1
fi
done

for TEST_FILE in `echo $TEST_FILES`; do
cd build

echo "$0: running test '$TEST_FILE'"
OLD_FILES=$(find . -name "*.gcda")

# folder for test results
TEST_RESULT_PATH=$(realpath /tmp/$RANDOM)
mkdir -p $TEST_RESULT_PATH
for FILE in $OLD_FILES; do
echo "$0: removing old coverage file '$FILE'"
rm $FILE
done

# run the test
rostest $PACKAGE $TEST_FILE $TEXT_OUTPUT --results-filename=$PACKAGE.test --results-base-dir="$TEST_RESULT_PATH"
cd $ORIGINAL_PATH

# evaluate the test results
echo test result path is $TEST_RESULT_PATH
catkin_test_results "$TEST_RESULT_PATH"
# build the package
catkin build --this # it has to be fully built normally before building with --catkin-make-args tests
catkin build --this --no-deps --catkin-make-args tests

done
catkin test --this -i -p 1 -s
7 changes: 0 additions & 7 deletions ros_packages/mrs_uav_gazebo_simulation/test/basic/basic.test

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

Loading

0 comments on commit b27bc2e

Please sign in to comment.