Skip to content

Commit

Permalink
updated tests
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Feb 11, 2024
1 parent 4af55fe commit 46b897e
Show file tree
Hide file tree
Showing 10 changed files with 103 additions and 146 deletions.
3 changes: 0 additions & 3 deletions test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,6 @@ find_package(rostest REQUIRED)
# will test takeoff in mrs simulator
add_subdirectory(takeoff)

# will test takeoff in gazebo
add_subdirectory(gazebo_takeoff)

# will test if takeoff is not allowed outside of safety area
add_subdirectory(outside_safety_area)

Expand Down
2 changes: 1 addition & 1 deletion test/compile_tests.sh
Original file line number Diff line number Diff line change
Expand Up @@ -6,5 +6,5 @@ trap 'last_command=$current_command; current_command=$BASH_COMMAND' DEBUG
trap 'echo "$0: \"${last_command}\" command failed with exit code $?"' ERR

# build the package
catkin build --this # it has to be fully built normally before building with --catkin-make-args tests
catkin build --this -DMRS_ENABLE_TESTING=1 --no-deps # it has to be fully built normally before building with --catkin-make-args tests
catkin build --this -DMRS_ENABLE_TESTING=1 --no-deps --catkin-make-args tests
16 changes: 0 additions & 16 deletions test/gazebo_takeoff/CMakeLists.txt

This file was deleted.

35 changes: 0 additions & 35 deletions test/gazebo_takeoff/gazebo_takeoff.test

This file was deleted.

62 changes: 0 additions & 62 deletions test/gazebo_takeoff/test.cpp

This file was deleted.

27 changes: 21 additions & 6 deletions test/moving_drone/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,28 @@ void Tester::timerMain([[maybe_unused]] const ros::TimerEvent& event) {

bool Tester::test() {

auto [success, message] = takeoff();
std::shared_ptr<mrs_uav_testing::UAVHandler> uh;

if (!success) {
return true;
} else {
ROS_ERROR("[%s]: takeoff initiated, this should not be possible", ros::this_node::getName().c_str());
return false;
{
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->takeoff();

if (!success) {
return true;
} else {
ROS_ERROR("[%s]: takeoff initiated, this should not be possible", ros::this_node::getName().c_str());
return false;
}
}
}

Expand Down
27 changes: 21 additions & 6 deletions test/outside_safety_area/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,28 @@ class Tester : public mrs_uav_testing::TestGeneric {

bool Tester::test() {

auto [success, message] = takeoff();
std::shared_ptr<mrs_uav_testing::UAVHandler> uh;

if (!success) {
return true;
} else {
ROS_ERROR("[%s]: takeoff initiated, this should not be possible", ros::this_node::getName().c_str());
return false;
{
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->takeoff();

if (!success) {
return true;
} else {
ROS_ERROR("[%s]: takeoff initiated, this should not be possible", ros::this_node::getName().c_str());
return false;
}
}
}

Expand Down
25 changes: 20 additions & 5 deletions test/takeoff/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,16 +10,31 @@ class Tester : public mrs_uav_testing::TestGeneric {

bool Tester::test() {

auto [success, message] = takeoff();
std::shared_ptr<mrs_uav_testing::UAVHandler> uh;

if (!success) {
ROS_ERROR("[%s]: takeoff failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
return false;
{
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->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()) {
if (uh->isFlyingNormally()) {
return true;
} else {
ROS_ERROR("[%s]: not flying normally", ros::this_node::getName().c_str());
Expand Down
27 changes: 21 additions & 6 deletions test/topic_check/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,28 @@ class Tester : public mrs_uav_testing::TestGeneric {

bool Tester::test() {

auto [success, message] = takeoff();
std::shared_ptr<mrs_uav_testing::UAVHandler> uh;

if (!success) {
return true;
} else {
ROS_ERROR("[%s]: takeoff initiated, this should not be possible: '%s'", ros::this_node::getName().c_str(), message.c_str());
return false;
{
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->takeoff();

if (!success) {
return true;
} else {
ROS_ERROR("[%s]: takeoff initiated, this should not be possible: '%s'", ros::this_node::getName().c_str(), message.c_str());
return false;
}
}
}

Expand Down
25 changes: 19 additions & 6 deletions test/without_takeoff/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,19 @@ Tester::Tester() : mrs_uav_testing::TestGeneric() {

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

// | ---------------- wait for ready to takeoff --------------- |

while (true) {
Expand All @@ -30,7 +43,7 @@ bool Tester::test() {

ROS_INFO_THROTTLE(1.0, "[%s]: waiting for the MRS UAV System", name_.c_str());

if (mrsSystemReady()) {
if (uh->mrsSystemReady()) {
ROS_INFO("[%s]: MRS UAV System is ready", name_.c_str());
break;
}
Expand All @@ -47,7 +60,7 @@ bool Tester::test() {
srv.request.data = true;

{
bool service_call = sch_arming_.call(srv);
bool service_call = uh->sch_arming_.call(srv);

if (!service_call || !srv.response.success) {
return false;
Expand All @@ -61,7 +74,7 @@ bool Tester::test() {

// | --------------------- check if armed --------------------- |

if (!sh_hw_api_status_.getMsg()->armed) {
if (!uh->sh_hw_api_status_.getMsg()->armed) {
return false;
}

Expand All @@ -71,7 +84,7 @@ bool Tester::test() {
std_srvs::Trigger srv;

{
bool service_call = sch_offboard_.call(srv);
bool service_call = uh->sch_offboard_.call(srv);

if (!service_call || !srv.response.success) {
return false;
Expand All @@ -85,7 +98,7 @@ bool Tester::test() {

// | ------------------ check if in offboard ------------------ |

if (!sh_hw_api_status_.getMsg()->offboard) {
if (!uh->sh_hw_api_status_.getMsg()->offboard) {
return false;
}

Expand Down Expand Up @@ -115,7 +128,7 @@ bool Tester::test() {

ROS_INFO_THROTTLE(1.0, "[%s]: waiting for the takeoff to finish", name_.c_str());

if (sh_control_manager_diag_.getMsg()->flying_normally) {
if (uh->sh_control_manager_diag_.getMsg()->flying_normally) {

return true;
}
Expand Down

0 comments on commit 46b897e

Please sign in to comment.