-
Notifications
You must be signed in to change notification settings - Fork 1.8k
Draft: accept empty yaml_filename #2929
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from all commits
80a7df5
0dd7fce
8bfff4a
7cf698f
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -94,7 +94,12 @@ Then, one would invoke this process with the params file that contains the param | |
| $ process_with_multiple_map_servers __params:=combined_params.yaml | ||
| ``` | ||
|
|
||
| #### Map Saver | ||
|
|
||
| The parameter for the initial map (yaml_filename) has to be set, but an empty string can be used if no initial map should be loaded. In this case, no map is loaded during | ||
| on_configure or published during on_activate. The _load_map_-service should the be used to load and publish a map. | ||
|
|
||
|
|
||
| ## Map Saver | ||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This name is intended to have 4 nesting level: here "Map Server" is a sub-chapter of "###CLI-usage" having nesting level equal to 3.
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Level 4 looks weird, 'Map Saver' is also on level two, but it's now on 4 |
||
|
|
||
| Like in ROS1 `map_saver` could be used as CLI-executable. It was renamed to `map_saver_cli` | ||
| and could be invoked by following command: | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -24,6 +24,8 @@ | |
| #include "nav2_map_server/map_server.hpp" | ||
| #include "nav2_util/lifecycle_service_client.hpp" | ||
| #include "nav2_msgs/srv/load_map.hpp" | ||
| using namespace std::chrono_literals; | ||
| using namespace rclcpp; | ||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Do we really need
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. yes, mostly for Parameter and ParameterValue |
||
|
|
||
| #define TEST_DIR TEST_DIRECTORY | ||
|
|
||
|
|
@@ -191,3 +193,46 @@ TEST_F(MapServerTestFixture, LoadMapInvalidImage) | |
|
|
||
| ASSERT_EQ(resp->result, nav2_msgs::srv::LoadMap::Response::RESULT_INVALID_MAP_DATA); | ||
| } | ||
|
|
||
NikolasE marked this conversation as resolved.
Show resolved
Hide resolved
|
||
|
|
||
| /** | ||
| * Test behaviour of server if yaml_filename is set to an empty string. | ||
| */ | ||
| TEST_F(MapServerTestFixture, NoInitialMap) | ||
| { | ||
| // turn off node into unconfigured state | ||
| lifecycle_client_->change_state(Transition::TRANSITION_DEACTIVATE); | ||
| lifecycle_client_->change_state(Transition::TRANSITION_CLEANUP); | ||
|
|
||
| auto client = node_->create_client<nav_msgs::srv::GetMap>("/map_server/map"); | ||
| auto req = std::make_shared<nav_msgs::srv::GetMap::Request>(); | ||
|
|
||
| auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node_, "map_server"); | ||
| ASSERT_TRUE(parameters_client->wait_for_service(3s)); | ||
SteveMacenski marked this conversation as resolved.
Show resolved
Hide resolved
|
||
|
|
||
| // set yaml_filename-parameter to empty string (essentially restart the node) | ||
| RCLCPP_INFO(node_->get_logger(), "Removing yaml_filename-parameter before restarting"); | ||
| parameters_client->set_parameters({Parameter("yaml_filename", ParameterValue(""))}); | ||
|
|
||
| // only configure node, to test behaviour of service while node is not active | ||
| lifecycle_client_->change_state(Transition::TRANSITION_CONFIGURE, 3s); | ||
|
|
||
| RCLCPP_INFO(node_->get_logger(), "Testing LoadMap service while not being active"); | ||
| auto load_map_req = std::make_shared<nav2_msgs::srv::LoadMap::Request>(); | ||
| auto load_map_cl = node_->create_client<nav2_msgs::srv::LoadMap>("/map_server/load_map"); | ||
|
|
||
| ASSERT_TRUE(load_map_cl->wait_for_service(3s)); | ||
| auto resp = send_request<nav2_msgs::srv::LoadMap>(node_, load_map_cl, load_map_req); | ||
|
|
||
| ASSERT_EQ(resp->result, nav2_msgs::srv::LoadMap::Response::RESULT_UNDEFINED_FAILURE); | ||
|
|
||
| // activate server and load map: | ||
| lifecycle_client_->change_state(Transition::TRANSITION_ACTIVATE, 3s); | ||
| RCLCPP_INFO(node_->get_logger(), "active again"); | ||
|
|
||
| load_map_req->map_url = path(TEST_DIR) / path(g_valid_yaml_file); | ||
| auto load_res = send_request<nav2_msgs::srv::LoadMap>(node_, load_map_cl, load_map_req); | ||
|
|
||
| ASSERT_EQ(load_res->result, nav2_msgs::srv::LoadMap::Response::RESULT_SUCCESS); | ||
| verifyMapMsg(load_res->map); | ||
| } | ||
Uh oh!
There was an error while loading. Please reload this page.