Skip to content

Commit 462f1e7

Browse files
added test for using default filepath
Signed-off-by: John Chrosniak <chrosniakj@gmail.com>
1 parent 911c361 commit 462f1e7

File tree

1 file changed

+21
-0
lines changed

1 file changed

+21
-0
lines changed

nav2_route/test/test_graph_saver.cpp

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,27 @@ TEST(GraphSaver, test_invalid_plugin)
5353
EXPECT_THROW(GraphSaver graph_saver(node, tf, frame), std::runtime_error);
5454
}
5555

56+
TEST(GraphSaver, test_empty_filename)
57+
{
58+
auto node = std::make_shared<nav2_util::LifecycleNode>("graph_saver_test");
59+
auto tf = std::make_shared<tf2_ros::Buffer>(node->get_clock());
60+
std::string frame = "map";
61+
62+
nav2_util::declare_parameter_if_not_declared(
63+
node, "graph_filepath", rclcpp::ParameterValue(
64+
ament_index_cpp::get_package_share_directory("nav2_route") +
65+
"/graphs/aws_graph.geojson"));
66+
67+
GraphLoader graph_loader(node, tf, frame);
68+
GraphSaver graph_saver(node, tf, frame);
69+
70+
Graph first_graph, second_graph;
71+
GraphToIDMap first_graph_to_id_map, second_graph_to_id_map;
72+
std::string file_path = "";
73+
graph_loader.loadGraphFromParameter(first_graph, first_graph_to_id_map);
74+
EXPECT_TRUE(graph_saver.saveGraphToFile(first_graph, file_path));
75+
}
76+
5677
TEST(GraphSaver, test_api)
5778
{
5879
auto node = std::make_shared<nav2_util::LifecycleNode>("graph_saver_test");

0 commit comments

Comments
 (0)