diff --git a/nav2_map_server/src/occ_grid_loader.cpp b/nav2_map_server/src/occ_grid_loader.cpp index 52b4e95e62..6cd4129bd2 100644 --- a/nav2_map_server/src/occ_grid_loader.cpp +++ b/nav2_map_server/src/occ_grid_loader.cpp @@ -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()); @@ -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 diff --git a/nav2_map_server/test/component/test_occ_grid_node.cpp b/nav2_map_server/test/component/test_occ_grid_node.cpp index 35bb42210f..4185a1cb4d 100644 --- a/nav2_map_server/test/component/test_occ_grid_node.cpp +++ b/nav2_map_server/test/component/test_occ_grid_node.cpp @@ -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(node_, client, req); ASSERT_EQ(resp->result, nav2_msgs::srv::LoadMap::Response::RESULT_SUCCESS); @@ -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(); - auto client = node_->create_client("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(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"); @@ -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(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) @@ -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(node_, client, req); @@ -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(node_, client, req);