diff --git a/.github/workflows/ros_build_test.yml b/.github/workflows/ros_build_test.yml index 27095107..f5703198 100644 --- a/.github/workflows/ros_build_test.yml +++ b/.github/workflows/ros_build_test.yml @@ -7,6 +7,7 @@ on: paths-ignore: - '**/README.md' + - 'test/**' pull_request: branches: [ master ] diff --git a/.github/workflows/ros_package_build.yml b/.github/workflows/ros_package_build.yml index d17da2a5..c7b1cd6d 100644 --- a/.github/workflows/ros_package_build.yml +++ b/.github/workflows/ros_package_build.yml @@ -7,6 +7,7 @@ on: paths-ignore: - '**/README.md' + - 'test/**' workflow_dispatch: diff --git a/test/control_manager/goto/test.cpp b/test/control_manager/goto/test.cpp index 08a06e33..338dee2f 100644 --- a/test/control_manager/goto/test.cpp +++ b/test/control_manager/goto/test.cpp @@ -1,5 +1,4 @@ #include -#include #include #include @@ -50,7 +49,7 @@ TEST(TESTSuite, goto) { mrs_lib::SubscribeHandler sh_estim_manager_diag = mrs_lib::SubscribeHandler(shopts, "/" + uav_name + "/estimation_manager/diagnostics"); - std::cout << "[Test]: subscribers initialized" << std::endl; + ROS_INFO("[%s]: subscribers initialized", ros::this_node::getName().c_str()); // | --------------------- service clients -------------------- | @@ -59,13 +58,13 @@ TEST(TESTSuite, goto) { mrs_lib::ServiceClientHandler(nh, "/" + uav_name + "/uav_manager/midair_activation"); mrs_lib::ServiceClientHandler sch_goto = mrs_lib::ServiceClientHandler(nh, "/" + uav_name + "/control_manager/goto"); - std::cout << "[Test]: service clients initialized" << std::endl; + ROS_INFO("[%s]: service client initialized", ros::this_node::getName().c_str()); // | ---------------- wait for ready to takeoff --------------- | while (ros::ok()) { - std::cout << "[Test]: waiting for 'ready to midair activation'" << std::endl; + ROS_INFO_THROTTLE(1.0, "[%s]: waiting for the MRS UAV System", ros::this_node::getName().c_str()); if (sh_control_manager_diag.hasMsg() && sh_estim_manager_diag.hasMsg()) { break; @@ -75,13 +74,13 @@ TEST(TESTSuite, goto) { ros::Duration(0.1).sleep(); } - std::cout << "[Test]: we are ready 'for midair activation'" << std::endl; + ROS_INFO("[%s]: MRS UAV System is ready", ros::this_node::getName().c_str()); ros::Duration(1.0).sleep(); // | ---------------------- arm the drone --------------------- | - std::cout << "[Test]: arming the drone" << std::endl; + ROS_INFO("[%s]: arming th edrone", ros::this_node::getName().c_str()); std_srvs::SetBool arming; arming.request.data = true; @@ -94,7 +93,7 @@ TEST(TESTSuite, goto) { // | -------------------- midair activation ------------------- | - std::cout << "[Test]: activating the drone 'in mid air'" << std::endl; + ROS_INFO("[%s]: activating the drone 'in mid air'", ros::this_node::getName().c_str()); std_srvs::Trigger midair; @@ -115,7 +114,7 @@ TEST(TESTSuite, goto) { goto_cmd.request.goal[2] = 5.5; goto_cmd.request.goal[3] = 2.2; - std::cout << "[Test]: calling goto" << std::endl; + ROS_INFO("[%s]: calling goto", ros::this_node::getName().c_str()); sch_goto.call(goto_cmd); @@ -123,7 +122,7 @@ TEST(TESTSuite, goto) { while (ros::ok()) { - std::cout << "[Test]: waiting for the goto" << std::endl; + ROS_INFO_THROTTLE(1.0, "[%s]: waiting for goto", ros::this_node::getName().c_str()); auto diag = sh_estim_manager_diag.getMsg(); @@ -138,7 +137,7 @@ TEST(TESTSuite, goto) { } ros::spinOnce(); - ros::Duration(1.0).sleep(); + ros::Duration(0.01).sleep(); } ROS_INFO("[%s]: finished", ros::this_node::getName().c_str()); diff --git a/test/run_test.sh b/test/run_test.sh deleted file mode 100755 index 724ff863..00000000 --- a/test/run_test.sh +++ /dev/null @@ -1,35 +0,0 @@ -#!/bin/bash - -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_managers" -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 --catkin-make-args tests - -# folder for test results -TEST_RESULT_PATH=$(realpath /tmp/$RANDOM) -mkdir -p $TEST_RESULT_PATH - -# run the test -rostest $PACKAGE control_manager_goto.test $TEXT_OUTPUT --results-filename=$PACKAGE.test --results-base-dir="$TEST_RESULT_PATH" - -# evaluate the test results -echo test result path is $TEST_RESULT_PATH -catkin_test_results "$TEST_RESULT_PATH" -success=$? - -echo "" -if [ $success = "0" ]; then - echo -e "\033[0;32mSuccess! \033[1;" -else - echo -e "\033[0;31mFailed some tests! \033[1;" -fi diff --git a/test/run_tests.sh b/test/run_tests.sh new file mode 100755 index 00000000..d962a90b --- /dev/null +++ b/test/run_tests.sh @@ -0,0 +1,33 @@ +#!/bin/bash + +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_managers" +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 --catkin-make-args tests + +TEST_FILES=$(find . -name "*.test" -type f -printf "%f\n") + +for TEST_FILE in `echo $TEST_FILES`; do + + # folder for test results + TEST_RESULT_PATH=$(realpath /tmp/$RANDOM) + mkdir -p $TEST_RESULT_PATH + + # run the test + rostest $PACKAGE $TEST_FILE $TEXT_OUTPUT --results-filename=$PACKAGE.test --results-base-dir="$TEST_RESULT_PATH" + + # evaluate the test results + echo test result path is $TEST_RESULT_PATH + catkin_test_results "$TEST_RESULT_PATH" + +done diff --git a/test/uav_manager/takeoff/test.cpp b/test/uav_manager/takeoff/test.cpp index 0cf953d1..f3e0ff24 100644 --- a/test/uav_manager/takeoff/test.cpp +++ b/test/uav_manager/takeoff/test.cpp @@ -12,10 +12,6 @@ #include #include -#include - -#include - /* TEST(TESTSuite, takeoff) //{ */ TEST(TESTSuite, takeoff) { @@ -24,10 +20,10 @@ TEST(TESTSuite, takeoff) { // | ------------------ initialize test node ------------------ | - std::cout << "[Test]: initializing the test node" << std::endl; - ros::NodeHandle nh = ros::NodeHandle("~"); + ROS_INFO("[%s]: ROS node initialized", ros::this_node::getName().c_str()); + ros::Time::waitForValid(); std::string uav_name = "uav1"; @@ -48,20 +44,20 @@ TEST(TESTSuite, takeoff) { mrs_lib::SubscribeHandler sh_control_manager_diag = mrs_lib::SubscribeHandler(shopts, "/" + uav_name + "/control_manager/diagnostics"); - std::cout << "[Test]: subscribers initialized" << std::endl; + ROS_INFO("[%s]: subscribers initialized", ros::this_node::getName().c_str()); // | --------------------- service clients -------------------- | mrs_lib::ServiceClientHandler sch_arming = mrs_lib::ServiceClientHandler(nh, "/" + uav_name + "/hw_api/arming"); mrs_lib::ServiceClientHandler sch_offboard = mrs_lib::ServiceClientHandler(nh, "/" + uav_name + "/hw_api/offboard"); - std::cout << "[Test]: service clients initialized" << std::endl; + ROS_INFO("[%s]: service clients initialized", ros::this_node::getName().c_str()); // | ---------------- wait for ready to takeoff --------------- | while (ros::ok()) { - std::cout << "[Test]: waiting for 'ready to takeoff'" << std::endl; + ROS_INFO_THROTTLE(1.0, "[%s]: waiting for the MRS UAV System", ros::this_node::getName().c_str()); if (sh_can_takeoff.hasMsg() && sh_can_takeoff.getMsg()->data) { break; @@ -71,11 +67,9 @@ TEST(TESTSuite, takeoff) { ros::Duration(0.1).sleep(); } - std::cout << "[Test]: ready for takeoff" << std::endl; - // | ---------------------- arm the drone --------------------- | - std::cout << "[Test]: arming the drone" << std::endl; + ROS_INFO("[%s]: arming the drone", ros::this_node::getName().c_str()); std_srvs::SetBool arming; arming.request.data = true; @@ -88,7 +82,7 @@ TEST(TESTSuite, takeoff) { // | -------------------- trigger offboard -------------------- | - std::cout << "[Test]: triggering offboard" << std::endl; + ROS_INFO("[%s]: triggering offboard", ros::this_node::getName().c_str()); std_srvs::Trigger offboard; @@ -98,7 +92,7 @@ TEST(TESTSuite, takeoff) { while (ros::ok()) { - std::cout << "[Test]: waiting for the takeoff to finish" << std::endl; + ROS_INFO_THROTTLE(1.0, "[%s]: waiting for the takeoff to finish", ros::this_node::getName().c_str()); if (sh_control_manager_diag.getMsg()->flying_normally) { result = 1; @@ -109,7 +103,7 @@ TEST(TESTSuite, takeoff) { ros::Duration(0.1).sleep(); } - std::cout << "[Test]: finished" << std::endl; + ROS_INFO("[%s]: finished", ros::this_node::getName().c_str()); EXPECT_TRUE(result); } @@ -120,7 +114,7 @@ int main([[maybe_unused]] int argc, [[maybe_unused]] char** argv) { testing::InitGoogleTest(&argc, argv); - ros::init(argc, argv, "Test"); + ros::init(argc, argv, "takeoff_test"); return RUN_ALL_TESTS(); }