Skip to content

Commit

Permalink
Increase test coverage
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexeyMerzlyakov committed Apr 22, 2020
1 parent 89ece96 commit 0db44c7
Show file tree
Hide file tree
Showing 14 changed files with 677 additions and 79 deletions.
34 changes: 33 additions & 1 deletion nav2_map_server/test/component/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
include_directories(${PROJECT_SOURCE_DIR}/test)

# map_server component test
ament_add_gtest_executable(test_map_server_node
test_map_server_node.cpp
${PROJECT_SOURCE_DIR}/test/test_constants.cpp
Expand All @@ -10,7 +11,6 @@ target_link_libraries(test_map_server_node
stdc++fs
)

# map_server component test
ament_add_test(test_map_server_node
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_map_server_launch.py"
Expand All @@ -20,3 +20,35 @@ ament_add_test(test_map_server_node
TEST_LAUNCH_DIR=${TEST_LAUNCH_DIR}
TEST_EXECUTABLE=$<TARGET_FILE:test_map_server_node>
)

# map_saver component test
ament_add_gtest_executable(test_map_saver_node
test_map_saver_node.cpp
${PROJECT_SOURCE_DIR}/test/test_constants.cpp
)

ament_target_dependencies(test_map_saver_node rclcpp nav_msgs)
target_link_libraries(test_map_saver_node
${library_name}
stdc++fs
)

add_executable(test_map_saver_publisher
test_map_saver_publisher.cpp
${PROJECT_SOURCE_DIR}/test/test_constants.cpp
)

target_link_libraries(test_map_saver_publisher
${map_io_library_name}
stdc++fs
)

ament_add_test(test_map_saver_node
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_map_saver_launch.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
ENV
TEST_DIR=${TEST_DIR}
TEST_LAUNCH_DIR=${TEST_LAUNCH_DIR}
TEST_EXECUTABLE=$<TARGET_FILE:test_map_saver_node>
)
47 changes: 47 additions & 0 deletions nav2_map_server/test/component/test_map_saver_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
#!/usr/bin/env python3

# Copyright (c) 2018 Intel Corporation
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import os
import sys

from launch import LaunchDescription
from launch import LaunchService
from launch.actions import ExecuteProcess
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_testing.legacy import LaunchTestService


def main(argv=sys.argv[1:]):
launchFile = os.path.join(os.getenv('TEST_LAUNCH_DIR'), 'map_saver_node.launch.py')
testExecutable = os.getenv('TEST_EXECUTABLE')
ld = LaunchDescription([
IncludeLaunchDescription(PythonLaunchDescriptionSource([launchFile])),
])
test1_action = ExecuteProcess(
cmd=[testExecutable],
name='test_map_saver_node',
)
lts = LaunchTestService()
lts.add_test_action(ld, test1_action)
ls = LaunchService(argv=argv)
ls.include_launch_description(ld)
os.chdir(os.getenv('TEST_LAUNCH_DIR'))
return lts.run(ls)


if __name__ == '__main__':
sys.exit(main())
218 changes: 218 additions & 0 deletions nav2_map_server/test/component/test_map_saver_node.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,218 @@
// Copyright (c) 2020 Samsung Research Russia
// Copyright (c) 2018 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gtest/gtest.h>
#include <experimental/filesystem>
#include <rclcpp/rclcpp.hpp>
#include <string>
#include <memory>

#include "test_constants/test_constants.h"
#include "nav2_map_server/map_saver.hpp"
#include "nav2_util/lifecycle_service_client.hpp"
#include "nav2_msgs/srv/save_map.hpp"

#define TEST_DIR TEST_DIRECTORY

using std::experimental::filesystem::path;
using lifecycle_msgs::msg::Transition;
using namespace nav2_map_server; // NOLINT

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};

RclCppFixture g_rclcppfixture;

class TestNode : public ::testing::Test
{
public:
TestNode()
{
node_ = rclcpp::Node::make_shared("map_client_test");
map_server_node_name_ = "map_saver";
lifecycle_client_ =
std::make_shared<nav2_util::LifecycleServiceClient>(map_server_node_name_, node_);
RCLCPP_INFO(node_->get_logger(), "Creating Test Node");


std::this_thread::sleep_for(std::chrono::seconds(1)); // allow node to start up
const std::chrono::seconds timeout(5);
lifecycle_client_->change_state(Transition::TRANSITION_CONFIGURE, timeout);
lifecycle_client_->change_state(Transition::TRANSITION_ACTIVATE, timeout);
}

~TestNode()
{
lifecycle_client_->change_state(Transition::TRANSITION_DEACTIVATE);
lifecycle_client_->change_state(Transition::TRANSITION_CLEANUP);
}

template<class T>
typename T::Response::SharedPtr send_request(

rclcpp::Node::SharedPtr node,
typename rclcpp::Client<T>::SharedPtr client,
typename T::Request::SharedPtr request)
{
auto result = client->async_send_request(request);

// Wait for the result
if (
rclcpp::spin_until_future_complete(node, result) ==
rclcpp::executor::FutureReturnCode::SUCCESS)
{
return result.get();
} else {
return nullptr;
}
}

protected:
// Check that map_msg corresponds to reference pattern
// Input: map_msg
void verifyMapMsg(const nav_msgs::msg::OccupancyGrid & map_msg)
{
ASSERT_FLOAT_EQ(map_msg.info.resolution, g_valid_image_res);
ASSERT_EQ(map_msg.info.width, g_valid_image_width);
ASSERT_EQ(map_msg.info.height, g_valid_image_height);
for (unsigned int i = 0; i < map_msg.info.width * map_msg.info.height; i++) {
ASSERT_EQ(g_valid_image_content[i], map_msg.data[i]);
}
}

std::string map_server_node_name_;
rclcpp::Node::SharedPtr node_;
std::shared_ptr<nav2_util::LifecycleServiceClient> lifecycle_client_;
};

// Send map saving service request.
// Load saved map and verify obtained OccupancyGrid.
TEST_F(TestNode, SaveMap)
{
RCLCPP_INFO(node_->get_logger(), "Testing SaveMap service");
auto req = std::make_shared<nav2_msgs::srv::SaveMap::Request>();
auto client = node_->create_client<nav2_msgs::srv::SaveMap>(
"/" + map_server_node_name_ + "/save_map");

RCLCPP_INFO(node_->get_logger(), "Waiting for save_map service");
ASSERT_TRUE(client->wait_for_service());

// 1. Send valid save_map serivce request
req->map_topic = "map";
req->map_url = path(g_tmp_dir) / path(g_valid_map_name);
req->image_format = "png";
req->map_mode = "trinary";
req->free_thresh = g_default_free_thresh;
req->occupied_thresh = g_default_occupied_thresh;
auto resp = send_request<nav2_msgs::srv::SaveMap>(node_, client, req);
ASSERT_EQ(resp->result, true);

// 2. Load saved map and verify it
nav_msgs::msg::OccupancyGrid map_msg;
LOAD_MAP_STATUS status = loadMapFromYaml(path(g_tmp_dir) / path(g_valid_yaml_file), map_msg);
ASSERT_EQ(status, LOAD_MAP_SUCCESS);
verifyMapMsg(map_msg);
}

// Send map saving service request with default parameters.
// Load saved map and verify obtained OccupancyGrid.
TEST_F(TestNode, SaveMapDefaultParameters)
{
RCLCPP_INFO(node_->get_logger(), "Testing SaveMap service");
auto req = std::make_shared<nav2_msgs::srv::SaveMap::Request>();
auto client = node_->create_client<nav2_msgs::srv::SaveMap>(
"/" + map_server_node_name_ + "/save_map");

RCLCPP_INFO(node_->get_logger(), "Waiting for save_map service");
ASSERT_TRUE(client->wait_for_service());

// 1. Send save_map serivce request with default parameters
req->map_topic = "";
req->map_url = path(g_tmp_dir) / path(g_valid_map_name);
req->image_format = "";
req->map_mode = "";
req->free_thresh = 0.0;
req->occupied_thresh = 0.0;
auto resp = send_request<nav2_msgs::srv::SaveMap>(node_, client, req);
ASSERT_EQ(resp->result, true);

// 2. Load saved map and verify it
nav_msgs::msg::OccupancyGrid map_msg;
LOAD_MAP_STATUS status = loadMapFromYaml(path(g_tmp_dir) / path(g_valid_yaml_file), map_msg);
ASSERT_EQ(status, LOAD_MAP_SUCCESS);
verifyMapMsg(map_msg);
}

// Send map saving service requests with different sets of parameters.
// In case of map is expected to be saved correctly, load map from a saved
// file and verify obtained OccupancyGrid.
TEST_F(TestNode, SaveMapInvalidParameters)
{
RCLCPP_INFO(node_->get_logger(), "Testing SaveMap service");
auto req = std::make_shared<nav2_msgs::srv::SaveMap::Request>();
auto client = node_->create_client<nav2_msgs::srv::SaveMap>(
"/" + map_server_node_name_ + "/save_map");

RCLCPP_INFO(node_->get_logger(), "Waiting for save_map service");
ASSERT_TRUE(client->wait_for_service());

// 1. Trying to send save_map serivce request with different sets of parameters
// In case of map is expected to be saved correctly, verify it
req->map_topic = "invalid_map";
req->map_url = path(g_tmp_dir) / path(g_valid_map_name);
req->image_format = "png";
req->map_mode = "trinary";
req->free_thresh = g_default_free_thresh;
req->occupied_thresh = g_default_occupied_thresh;
auto resp = send_request<nav2_msgs::srv::SaveMap>(node_, client, req);
ASSERT_EQ(resp->result, false);

req->map_topic = "map";
req->image_format = "invalid_format";
resp = send_request<nav2_msgs::srv::SaveMap>(node_, client, req);
ASSERT_EQ(resp->result, true);
nav_msgs::msg::OccupancyGrid map_msg;
LOAD_MAP_STATUS status = loadMapFromYaml(path(g_tmp_dir) / path(g_valid_yaml_file), map_msg);
ASSERT_EQ(status, LOAD_MAP_SUCCESS);
verifyMapMsg(map_msg);

req->image_format = "png";
req->map_mode = "invalid_mode";
resp = send_request<nav2_msgs::srv::SaveMap>(node_, client, req);
ASSERT_EQ(resp->result, true);
status = loadMapFromYaml(path(g_tmp_dir) / path(g_valid_yaml_file), map_msg);
ASSERT_EQ(status, LOAD_MAP_SUCCESS);
verifyMapMsg(map_msg);

req->map_mode = "trinary";
req->free_thresh = 2.0;
req->occupied_thresh = 2.0;
resp = send_request<nav2_msgs::srv::SaveMap>(node_, client, req);
ASSERT_EQ(resp->result, false);

req->free_thresh = -2.0;
req->occupied_thresh = -2.0;
resp = send_request<nav2_msgs::srv::SaveMap>(node_, client, req);
ASSERT_EQ(resp->result, false);

req->free_thresh = 0.7;
req->occupied_thresh = 0.2;
resp = send_request<nav2_msgs::srv::SaveMap>(node_, client, req);
ASSERT_EQ(resp->result, false);
}
68 changes: 68 additions & 0 deletions nav2_map_server/test/component/test_map_saver_publisher.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
// Copyright (c) 2020 Samsung Research Russia
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <experimental/filesystem>
#include <string>
#include <memory>
#include <chrono>

#include "rclcpp/rclcpp.hpp"
#include "nav2_map_server/map_io.hpp"
#include "test_constants/test_constants.h"

#define TEST_DIR TEST_DIRECTORY

using namespace std::chrono_literals;
using namespace nav2_map_server; // NOLINT
using std::experimental::filesystem::path;

class TestPublisher : public rclcpp::Node
{
public:
TestPublisher()
: Node("map_publisher")
{
std::string pub_map_file = path(TEST_DIR) / path(g_valid_yaml_file);
LOAD_MAP_STATUS status = loadMapFromYaml(pub_map_file, msg_);
if (status != LOAD_MAP_SUCCESS) {
RCLCPP_ERROR(get_logger(), "Can not load %s map file", pub_map_file);
return;
}

map_pub_ = create_publisher<nav_msgs::msg::OccupancyGrid>(
"map",
rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());

timer_ = create_wall_timer(300ms, std::bind(&TestPublisher::mapPublishCallback, this));
}

protected:
void mapPublishCallback()
{
map_pub_->publish(msg_);
}

rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr map_pub_;
rclcpp::TimerBase::SharedPtr timer_;
nav_msgs::msg::OccupancyGrid msg_;
};

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto pub_node = std::make_shared<TestPublisher>();
rclcpp::spin(pub_node);
rclcpp::shutdown();
return 0;
}
Loading

0 comments on commit 0db44c7

Please sign in to comment.