Skip to content

Commit

Permalink
Update tests for URL support
Browse files Browse the repository at this point in the history
  • Loading branch information
Matthew Hansen committed Dec 3, 2019
1 parent c3784d5 commit f38818c
Showing 1 changed file with 10 additions and 13 deletions.
23 changes: 10 additions & 13 deletions nav2_map_server/test/component/test_occ_grid_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,8 +114,7 @@ TEST_F(TestNode, LoadMap)
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);
req->map_url = path("file://") / 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);
Expand All @@ -136,12 +135,13 @@ TEST_F(TestNode, LoadMapURL)
RCLCPP_INFO(node_->get_logger(), "Waiting for load_map service");
ASSERT_TRUE(client->wait_for_service());

req->type = nav2_msgs::srv::LoadMap::Request::TYPE_URL;
req->map_id = "dummy";
RCLCPP_INFO(node_->get_logger(), "Sending load_map request with invalid type");
req->map_url =
"https://raw.githubusercontent.com/ros-planning/navigation2/master" +
"/nav2_map_server/test/testmap.yaml";
RCLCPP_INFO(node_->get_logger(), "Sending load_map request with http: url");
auto resp = send_request<nav2_msgs::srv::LoadMap>(node_, client, req);

ASSERT_EQ(resp->result, nav2_msgs::srv::LoadMap::Response::RESULT_INVALID_TYPE);
ASSERT_EQ(resp->result, nav2_msgs::srv::LoadMap::Response::RESULT_SUCCESS);
}

TEST_F(TestNode, LoadMapNull)
Expand All @@ -153,12 +153,11 @@ TEST_F(TestNode, LoadMapNull)
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 = "";
req->map_url = "";
RCLCPP_INFO(node_->get_logger(), "Sending load_map request with null file name");
auto resp = send_request<nav2_msgs::srv::LoadMap>(node_, client, req);

ASSERT_EQ(resp->result, nav2_msgs::srv::LoadMap::Response::RESULT_MAP_ID_DOES_NOT_EXIST);
ASSERT_EQ(resp->result, nav2_msgs::srv::LoadMap::Response::RESULT_MAP_DOES_NOT_EXIST);
}

TEST_F(TestNode, LoadMapInvalidYaml)
Expand All @@ -170,8 +169,7 @@ TEST_F(TestNode, LoadMapInvalidYaml)
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 = "invalid_file.yaml";
req->map_url = "invalid_file.yaml";
RCLCPP_INFO(node_->get_logger(), "Sending load_map request with invalid yaml file name");
auto resp = send_request<nav2_msgs::srv::LoadMap>(node_, client, req);

Expand All @@ -187,8 +185,7 @@ TEST_F(TestNode, LoadMapInvalidImage)
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 = req->map_id = path(TEST_DIR) / "invalid_image.yaml";
req->map_url = path("file://") / path(TEST_DIR) / "invalid_image.yaml";
RCLCPP_INFO(node_->get_logger(), "Sending load_map request with invalid image file name");
auto resp = send_request<nav2_msgs::srv::LoadMap>(node_, client, req);

Expand Down

0 comments on commit f38818c

Please sign in to comment.