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 e239a2b commit c4388b9
Show file tree
Hide file tree
Showing 4 changed files with 49 additions and 10 deletions.
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
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,21 @@ 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] = spawnGazeboUav();
auto [success, message] = uh->spawnGazeboUAV(_gazebo_spawner_params_);

if (!success) {
ROS_ERROR("[%s]: gazebo UAV spawning failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
Expand All @@ -20,7 +33,7 @@ bool Tester::test() {
}

{
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 @@ -30,7 +43,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
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,21 @@ 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] = spawnGazeboUav();
auto [success, message] = uh->spawnGazeboUAV(_gazebo_spawner_params_);

if (!success) {
ROS_ERROR("[%s]: gazebo UAV spawning failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
Expand All @@ -20,7 +33,7 @@ bool Tester::test() {
}

{
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 @@ -30,7 +43,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
19 changes: 16 additions & 3 deletions ros_packages/mrs_uav_gazebo_simulation/test/uav_models/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,21 @@ 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] = spawnGazeboUav();
auto [success, message] = uh->spawnGazeboUAV(_gazebo_spawner_params_);

if (!success) {
ROS_ERROR("[%s]: gazebo UAV spawning failed with message: '%s'", ros::this_node::getName().c_str(), message.c_str());
Expand All @@ -20,7 +33,7 @@ bool Tester::test() {
}

{
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 @@ -30,7 +43,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 c4388b9

Please sign in to comment.