Skip to content

Commit

Permalink
updated tests
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Jan 29, 2024
1 parent 988e5b4 commit aa90745
Show file tree
Hide file tree
Showing 11 changed files with 167 additions and 17 deletions.
1 change: 1 addition & 0 deletions ros_packages/mrs_uav_gazebo_simulation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ set(CATKIN_DEPENDENCIES
mrs_msgs
rospy
std_msgs
mrs_uav_testing
)

find_package(catkin REQUIRED COMPONENTS
Expand Down
3 changes: 1 addition & 2 deletions ros_packages/mrs_uav_gazebo_simulation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,10 @@
<depend>rospy</depend>
<depend>std_msgs</depend>
<depend>ignition-math6</depend>
<depend>mrs_uav_testing</depend>

<depend>python3-jinja2</depend>

<test_depend>mrs_uav_testing</test_depend>

<export>
<!-- gazebo_ros_paths_plugin automatically adds these to
GAZEBO_PLUGIN_PATH and GAZEBO_MODEL_PATH when you do this export inside
Expand Down
17 changes: 2 additions & 15 deletions ros_packages/mrs_uav_gazebo_simulation/test/takeoff/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,16 +1,3 @@
get_filename_component(TEST_NAME "${CMAKE_CURRENT_SOURCE_DIR}" NAME)
add_subdirectory(takeoff_gps_garmin)

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)
add_subdirectory(takeoff_gps_baro)
Original file line number Diff line number Diff line change
@@ -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)
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
# GET ALL PARAMETERS USABLE FOR CUSTOM CONFIG BY RUNNING:
## --------------------------------------------------------------
## | rosrun mrs_uav_core get_public_params.py #
## --------------------------------------------------------------

mrs_uav_managers:

estimation_manager:

# loaded state estimator plugins
state_estimators: [
"gps_baro",
]

initial_state_estimator: "gps_baro" # will be used as the first state estimator
agl_height_estimator: "" # only slightly filtered height for checking min height (not used in control feedback)
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
<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/gazebo_simulator.launch" />

<include file="$(find mrs_uav_px4_api)/launch/api.launch">
<arg name="UAV_NAME" default="$(arg UAV_NAME)" />
<arg name="RUN_TYPE" default="simulation" />
</include>

<include file="$(find mrs_uav_testing)/launch/mrs_uav_system.launch">
<arg name="automatic_start" default="true" />
<arg name="platform_config" default="$(find mrs_uav_gazebo_simulation)/config/mrs_uav_system/$(arg UAV_TYPE).yaml" />
<arg name="custom_config" default="$(dirname)/config/custom_config.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="120.0">
<param name="test_name" value="$(arg test_name)" />
<param name="uav_name" value="$(arg UAV_NAME)" />
<param name="gazebo_spawner_params" value="1 --$(arg UAV_TYPE)" />
</test>

</launch>
Original file line number Diff line number Diff line change
@@ -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)
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
# GET ALL PARAMETERS USABLE FOR CUSTOM CONFIG BY RUNNING:
## --------------------------------------------------------------
## | rosrun mrs_uav_core get_public_params.py #
## --------------------------------------------------------------

mrs_uav_managers:

estimation_manager:

# loaded state estimator plugins
state_estimators: [
"gps_garmin",
]

initial_state_estimator: "gps_garmin" # will be used as the first state estimator
agl_height_estimator: "garmin_agl" # only slightly filtered height for checking min height (not used in control feedback)
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
<include file="$(find mrs_uav_testing)/launch/mrs_uav_system.launch">
<arg name="automatic_start" default="true" />
<arg name="platform_config" default="$(find mrs_uav_gazebo_simulation)/config/mrs_uav_system/$(arg UAV_TYPE).yaml" />
<arg name="custom_config" default="$(dirname)/config/custom_config.yaml" />
<arg name="UAV_NAME" default="$(arg UAV_NAME)" />
</include>

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
#include <gtest/gtest.h>

#include <mrs_uav_testing/test_generic.h>

class Tester : public mrs_uav_testing::TestGeneric {

public:
bool test();
};

bool Tester::test() {

{
auto [success, message] = spawnGazeboUav();

if (!success) {
ROS_ERROR("[%s]: gazebo UAV spawning failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
return false;
}
}

{
auto [success, message] = takeoff();

if (!success) {
ROS_ERROR("[%s]: takeoff failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
return false;
}
}

this->sleep(5.0);

if (this->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();
}

0 comments on commit aa90745

Please sign in to comment.