diff --git a/test/control_manager/goto_fcu_service/CMakeLists.txt b/test/control_manager/goto_fcu_service/CMakeLists.txt new file mode 100644 index 0000000..bf8f985 --- /dev/null +++ b/test/control_manager/goto_fcu_service/CMakeLists.txt @@ -0,0 +1,16 @@ +get_filename_component(TEST_NAME "${CMAKE_CURRENT_SOURCE_DIR}" NAME) + +catkin_add_executable_with_gtest(test_${TEST_NAME} + test.cpp + ) + +target_link_libraries(test_${TEST_NAME} + ${catkin_LIBRARIES} + ) + +add_dependencies(test_${TEST_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ) + +add_rostest(${TEST_NAME}.test) diff --git a/test/control_manager/goto_fcu_service/goto_fcu_service.test b/test/control_manager/goto_fcu_service/goto_fcu_service.test new file mode 100644 index 0000000..604b743 --- /dev/null +++ b/test/control_manager/goto_fcu_service/goto_fcu_service.test @@ -0,0 +1,35 @@ +<launch> + + <arg name="this_path" default="$(dirname)" /> + + <arg name="UAV_NAME" default="uav1" /> + <arg name="UAV_TYPE" default="x500" /> + + <!-- automatically deduce the test name --> + <arg name="test_name" default="$(eval arg('this_path').split('/')[-1])" /> + + <!-- automatically deduce the package name --> + <arg name="import_eval" default="eval('_' + '_import_' + '_')"/> + <arg name="package_eval" default="eval(arg('import_eval') + '(\'rospkg\')').get_package_name(arg('this_path'))" /> + <arg name="package" default="$(eval eval(arg('package_eval')))" /> + + <include file="$(find mrs_uav_testing)/launch/mrs_simulator.launch"> + <arg name="UAV_NAME" default="$(arg UAV_NAME)" /> + </include> + + <include file="$(find mrs_multirotor_simulator)/launch/hw_api.launch"> + <arg name="UAV_NAME" default="$(arg UAV_NAME)" /> + </include> + + <include file="$(find mrs_uav_testing)/launch/mrs_uav_system.launch"> + <arg name="automatic_start" default="false" /> + <arg name="platform_config" default="$(find mrs_multirotor_simulator)/config/mrs_uav_system/$(arg UAV_TYPE).yaml" /> + <arg name="UAV_NAME" default="$(arg UAV_NAME)" /> + </include> + + <test pkg="$(arg package)" type="test_$(arg test_name)" test-name="$(arg test_name)" time-limit="60.0"> + <param name="test" value="$(arg test_name)" /> + <param name="uav_name" value="$(arg UAV_NAME)" /> + </test> + +</launch> diff --git a/test/control_manager/goto_fcu_service/test.cpp b/test/control_manager/goto_fcu_service/test.cpp new file mode 100644 index 0000000..4566cce --- /dev/null +++ b/test/control_manager/goto_fcu_service/test.cpp @@ -0,0 +1,74 @@ +#include <gtest/gtest.h> + +#include <mrs_uav_testing/test_generic.h> + +class Tester : public mrs_uav_testing::TestGeneric { + +public: + bool test(); +}; + +bool Tester::test() { + + std::shared_ptr<mrs_uav_testing::UAVHandler> uh; + + { + auto [uhopt, message] = getUAVHandler(_uav_name_); + + if (!uhopt) { + ROS_ERROR("[%s]: Failed obtain handler for '%s': '%s'", ros::this_node::getName().c_str(), _uav_name_.c_str(), message.c_str()); + return false; + } + + uh = uhopt.value(); + } + + { + auto [success, message] = uh->activateMidAir(); + + if (!success) { + ROS_ERROR("[%s]: midair activation failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str()); + return false; + } + } + + { + auto [success, message] = uh->gotoFcu(3, 2, 1, 1); + + if (!success) { + ROS_ERROR("[%s]: goto_fcu failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str()); + return false; + } + } + + this->sleep(5.0); + + if (uh->isFlyingNormally()) { + return true; + } else { + ROS_ERROR("[%s]: not flying normally", ros::this_node::getName().c_str()); + return false; + } +} + +TEST(TESTSuite, test) { + + Tester tester; + + bool result = tester.test(); + + if (result) { + GTEST_SUCCEED(); + } else { + GTEST_FAIL(); + } +} + +int main([[maybe_unused]] int argc, [[maybe_unused]] char** argv) { + + ros::init(argc, argv, "test"); + + testing::InitGoogleTest(&argc, argv); + + return RUN_ALL_TESTS(); +}