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 42a7032 commit 1d0f3eb
Show file tree
Hide file tree
Showing 4 changed files with 53 additions and 14 deletions.
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 --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
23 changes: 18 additions & 5 deletions test/landoff_tracker/takeoff_landing/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,23 @@ class Tester : public 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();
}

// | ------------------------- takeoff ------------------------ |

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

if (!success) {
ROS_ERROR("[%s]: takeoff failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
Expand All @@ -23,15 +36,15 @@ bool Tester::test() {

this->sleep(1.0);

if (!this->isFlyingNormally()) {
if (!uh->isFlyingNormally()) {
ROS_ERROR("[%s]: not flying normally", ros::this_node::getName().c_str());
return false;
}

// | --------------------- goto somewhere --------------------- |

{
auto [success, message] = gotoRel(10, 1, 2, 1.5);
auto [success, message] = uh->gotoRel(10, 1, 2, 1.5);

if (!success) {
ROS_ERROR("[%s]: goto failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
Expand All @@ -41,15 +54,15 @@ bool Tester::test() {

this->sleep(1.0);

if (!this->isFlyingNormally()) {
if (!uh->isFlyingNormally()) {
ROS_ERROR("[%s]: not flying normally", ros::this_node::getName().c_str());
return false;
}

// | -------------------------- land -------------------------- |

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

if (!success) {
ROS_ERROR("[%s]: landing failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
Expand Down
21 changes: 17 additions & 4 deletions test/line_tracker/line_tracker_goto/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,22 +10,35 @@ class Tester : public 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();
}

{
auto [success, message] = activateMidAir();
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;
}
}

if (this->getActiveTracker() != "LineTracker") {
if (uh->getActiveTracker() != "LineTracker") {
ROS_ERROR("[%s]: LineTracker is not active", ros::this_node::getName().c_str());
return false;
}

{
auto [success, message] = this->gotoRel(10, 1, 2, 1.5);
auto [success, message] = uh->gotoRel(10, 1, 2, 1.5);

if (!success) {
ROS_ERROR("[%s]: goto failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
Expand All @@ -35,7 +48,7 @@ bool Tester::test() {

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
21 changes: 17 additions & 4 deletions test/mpc_tracker/mpc_tracker_goto/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,22 +10,35 @@ class Tester : public 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();
}

{
auto [success, message] = activateMidAir();
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;
}
}

if (this->getActiveTracker() != "MpcTracker") {
if (uh->getActiveTracker() != "MpcTracker") {
ROS_ERROR("[%s]: MpcTracker is not active", ros::this_node::getName().c_str());
return false;
}

{
auto [success, message] = this->gotoRel(10, 1, 2, 1.5);
auto [success, message] = uh->gotoRel(10, 1, 2, 1.5);

if (!success) {
ROS_ERROR("[%s]: goto failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
Expand All @@ -35,7 +48,7 @@ bool Tester::test() {

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

0 comments on commit 1d0f3eb

Please sign in to comment.