Skip to content

Commit

Permalink
Update for new LoadMap service
Browse files Browse the repository at this point in the history
  • Loading branch information
Matthew Hansen committed Dec 6, 2019
1 parent add1ffb commit 1f52a51
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 35 deletions.
11 changes: 2 additions & 9 deletions nav2_map_server/src/occ_grid_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ bool OccGridLoader::loadMapFromYaml(
{
if (yaml_file.empty()) {
RCLCPP_ERROR(node_->get_logger(), "YAML file name is empty, can't load!");
response->result = nav2_msgs::srv::LoadMap::Response::RESULT_MAP_ID_DOES_NOT_EXIST;
response->result = nav2_msgs::srv::LoadMap::Response::RESULT_MAP_DOES_NOT_EXIST;
return false;
}
RCLCPP_INFO(node_->get_logger(), "Loading yaml file: %s", yaml_file.c_str());
Expand Down Expand Up @@ -206,15 +206,8 @@ nav2_util::CallbackReturn OccGridLoader::on_configure(const rclcpp_lifecycle::St
return;
}
RCLCPP_INFO(node_->get_logger(), "OccGridLoader: Handling LoadMap request");
// Check if map_id is a file
if (request->type != nav2_msgs::srv::LoadMap::Request::TYPE_FILE) {
RCLCPP_ERROR(node_->get_logger(),
"OccGridLoader: unsupported FILE_TYPE in request, can't load map");
response->result = nav2_msgs::srv::LoadMap::Response::RESULT_INVALID_TYPE;
return;
}
// Load from file
if (loadMapFromYaml(request->map_id, response)) {
if (loadMapFromYaml(request->map_url, response)) {
response->map = *msg_;
response->result = nav2_msgs::srv::LoadMap::Response::RESULT_SUCCESS;
occ_pub_->publish(*msg_); // publish new map
Expand Down
31 changes: 5 additions & 26 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(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 @@ -127,23 +126,6 @@ TEST_F(TestNode, LoadMap)
}
}

TEST_F(TestNode, LoadMapURL)
{
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_URL;
req->map_id = "dummy";
RCLCPP_INFO(node_->get_logger(), "Sending load_map request with invalid type");
auto resp = send_request<nav2_msgs::srv::LoadMap>(node_, client, req);

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

TEST_F(TestNode, LoadMapNull)
{
RCLCPP_INFO(node_->get_logger(), "Testing LoadMap service");
Expand All @@ -153,12 +135,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 +151,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 +167,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(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 1f52a51

Please sign in to comment.