Skip to content

Commit

Permalink
added hover test
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Apr 29, 2024
1 parent fe483ae commit e06f30b
Show file tree
Hide file tree
Showing 5 changed files with 183 additions and 0 deletions.
2 changes: 2 additions & 0 deletions test/control_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,3 +27,5 @@ add_subdirectory(set_heading_service)
add_subdirectory(set_heading_relative_service)

add_subdirectory(goto_altitude_service)

add_subdirectory(hover_service)
16 changes: 16 additions & 0 deletions test/control_manager/hover_service/CMakeLists.txt
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)
34 changes: 34 additions & 0 deletions test/control_manager/hover_service/config/world_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
world_origin:

units: "LATLON" # {"UTM, "LATLON"}

origin_x: 47.397743
origin_y: 8.545594

safety_area:

enabled: false

horizontal:

# the frame of reference in which the points are expressed
frame_name: "world_origin"

# polygon
#
# x, y [m] for any frame_name except latlon_origin
# x = latitude, y = longitude [deg] for frame_name=="latlon_origin"
points: [
-50, -50,
50, -50,
50, 50,
-50, 50,
]

vertical:

# the frame of reference in which the max&min z is expressed
frame_name: "world_origin"

max_z: 15.0
min_z: 0.5
36 changes: 36 additions & 0 deletions test/control_manager/hover_service/hover_service.test
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/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="world_config" default="$(dirname)/config/world_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="60.0">
<param name="test" value="$(arg test_name)" />
<param name="uav_name" value="$(arg UAV_NAME)" />
</test>

</launch>
95 changes: 95 additions & 0 deletions test/control_manager/hover_service/test.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,95 @@
#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;
}
}

// | ---------------------- goto relative --------------------- |

{
auto [success, message] = uh->gotoRelativeService(200, 0, 0, 0);

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

// | -------------------------- wait -------------------------- |

this->sleep(5.0);

// | ---------------------- trigger hover --------------------- |

{
auto [success, message] = uh->hover();

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

// | -------------------------- wait -------------------------- |

this->sleep(5.0);

// | --------------- check if we are stationary --------------- |

if (uh->isFlyingNormally() && uh->isStationary()) {
return true;
} else {
ROS_ERROR("[%s]: not flying normally || not stationary", 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 e06f30b

Please sign in to comment.