Skip to content
Snippets Groups Projects
Commit 6557025a authored by Matthew Hansen's avatar Matthew Hansen Committed by Matt Hansen
Browse files

Add LoadMap service test

parent 0e99ccf5
No related branches found
No related tags found
No related merge requests found
......@@ -13,12 +13,18 @@
// limitations under the License.
#include <gtest/gtest.h>
#include <experimental/filesystem>
#include <rclcpp/rclcpp.hpp>
#include <memory>
#include "test_constants/test_constants.h"
#include "nav2_map_server/occ_grid_loader.hpp"
#include "nav2_util/lifecycle_service_client.hpp"
#include "nav2_msgs/srv/load_map.hpp"
#define TEST_DIR TEST_DIRECTORY
using std::experimental::filesystem::path;
using lifecycle_msgs::msg::Transition;
......@@ -39,9 +45,11 @@ public:
node_ = rclcpp::Node::make_shared("map_client_test");
lifecycle_client_ =
std::make_shared<nav2_util::LifecycleServiceClient>("map_server", node_);
RCLCPP_INFO(node_->get_logger(), "Creating Test Node");
lifecycle_client_->change_state(Transition::TRANSITION_CONFIGURE);
lifecycle_client_->change_state(Transition::TRANSITION_ACTIVATE);
const std::chrono::seconds timeout(1);
lifecycle_client_->change_state(Transition::TRANSITION_CONFIGURE, timeout);
lifecycle_client_->change_state(Transition::TRANSITION_ACTIVATE, timeout);
}
~TestNode()
......@@ -75,11 +83,36 @@ protected:
std::shared_ptr<nav2_util::LifecycleServiceClient> lifecycle_client_;
};
TEST_F(TestNode, ResultReturned)
TEST_F(TestNode, LoadMap)
{
RCLCPP_INFO(node_->get_logger(), "Testing LoadMap service");
auto req = std::make_shared<nav2_msgs::srv::LoadMap::Request>();
auto client = node_->create_client<nav2_msgs::srv::LoadMap>("load_map");
RCLCPP_INFO(node_->get_logger(), "Waiting for load_map service");
ASSERT_TRUE(client->wait_for_service());
req->type = nav2_msgs::srv::LoadMap::Request::TYPE_FILE;
req->map_id = path(TEST_DIR) / path(g_valid_yaml_file);
auto resp = send_request<nav2_msgs::srv::LoadMap>(node_, client, req);
ASSERT_EQ(resp->result, nav2_msgs::srv::LoadMap::Response::RESULT_SUCCESS);
ASSERT_FLOAT_EQ(resp->map.info.resolution, g_valid_image_res);
ASSERT_EQ(resp->map.info.width, g_valid_image_width);
ASSERT_EQ(resp->map.info.height, g_valid_image_height);
for (unsigned int i = 0; i < resp->map.info.width * resp->map.info.height; i++) {
ASSERT_EQ(g_valid_image_content[i], resp->map.data[i]);
}
}
TEST_F(TestNode, GetMap)
{
RCLCPP_INFO(node_->get_logger(), "Testing GetMap service");
auto req = std::make_shared<nav_msgs::srv::GetMap::Request>();
auto client = node_->create_client<nav_msgs::srv::GetMap>("map");
RCLCPP_INFO(node_->get_logger(), "Waiting for map service");
ASSERT_TRUE(client->wait_for_service());
auto resp = send_request<nav_msgs::srv::GetMap>(node_, client, req);
......
......@@ -57,5 +57,6 @@ const char g_valid_image_content[] = {
const char * g_valid_png_file = "testmap.png";
const char * g_valid_bmp_file = "testmap.bmp";
const char * g_valid_yaml_file = "testmap.yaml";
const float g_valid_image_res = 0.1;
......@@ -38,6 +38,7 @@ extern const unsigned int g_valid_image_height;
extern const char g_valid_image_content[];
extern const char * g_valid_png_file;
extern const char * g_valid_bmp_file;
extern const char * g_valid_yaml_file;
extern const float g_valid_image_res;
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment