Skip to content

Commit

Permalink
Add expanding the ~/ to the full home dir of user in the path to the …
Browse files Browse the repository at this point in the history
…map yaml. (#4258)

* Add user home expander of home sequence

Signed-off-by: Wiktor Bajor <[email protected]>

* Add passing home dir as string instead of const char*

Signed-off-by: Wiktor Bajor <[email protected]>

* Add docs

Signed-off-by: Wiktor Bajor <[email protected]>

* Fix function declaration

Signed-off-by: Wiktor Bajor <[email protected]>

* Fix linter issues

Signed-off-by: Wiktor Bajor <[email protected]>

* Uncrustify linter

Signed-off-by: Wiktor Bajor <[email protected]>

* Uncrustify linter

Signed-off-by: Wiktor Bajor <[email protected]>

* Uncrustify linter: remove remove whitespace

Signed-off-by: Wiktor Bajor <[email protected]>

---------

Signed-off-by: Wiktor Bajor <[email protected]>
  • Loading branch information
Wiktor-99 authored Apr 11, 2024
1 parent 8af70ab commit 61a774b
Show file tree
Hide file tree
Showing 3 changed files with 64 additions and 2 deletions.
11 changes: 11 additions & 0 deletions nav2_map_server/include/nav2_map_server/map_io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,17 @@ bool saveMapToFile(
const nav_msgs::msg::OccupancyGrid & map,
const SaveParameters & save_parameters);

/**
* @brief Expand ~/ to home user dir.
* @param yaml_filename Name of input YAML file.
* @param home_dir Expanded `~/`home dir or empty string if HOME not set
*
* @return Expanded string or input string if `~/` not expanded
*/
std::string expand_user_home_dir_if_needed(
std::string yaml_filename,
std::string home_dir);

} // namespace nav2_map_server

#endif // NAV2_MAP_SERVER__MAP_IO_HPP_
28 changes: 26 additions & 2 deletions nav2_map_server/src/map_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <vector>
#include <fstream>
#include <stdexcept>
#include <cstdlib>

#include "Magick++.h"
#include "nav2_util/geometry_utils.hpp"
Expand Down Expand Up @@ -115,9 +116,33 @@ T yaml_get_value(const YAML::Node & node, const std::string & key)
}
}

std::string get_home_dir()
{
if (const char * home_dir = std::getenv("HOME")) {
return std::string{home_dir};
}
return std::string{};
}

std::string expand_user_home_dir_if_needed(
std::string yaml_filename,
std::string home_variable_value)
{
if (yaml_filename.size() < 2 || !(yaml_filename[0] == '~' && yaml_filename[1] == '/')) {
return yaml_filename;
}
if (home_variable_value.empty()) {
std::cout << "[INFO] [map_io]: Map yaml file name starts with '~/' but no HOME variable set. \n"
<< "[INFO] [map_io] User home dir will be not expanded \n";
return yaml_filename;
}
const std::string prefix{home_variable_value};
return yaml_filename.replace(0, 1, prefix);
}

LoadParameters loadMapYaml(const std::string & yaml_filename)
{
YAML::Node doc = YAML::LoadFile(yaml_filename);
YAML::Node doc = YAML::LoadFile(expand_user_home_dir_if_needed(yaml_filename, get_home_dir()));
LoadParameters load_parameters;

auto image_file_name = yaml_get_value<std::string>(doc, "image");
Expand Down Expand Up @@ -295,7 +320,6 @@ LOAD_MAP_STATUS loadMapFromYaml(
" for reason: " << e.what() << std::endl;
return INVALID_MAP_METADATA;
}

try {
loadMapFromFile(load_parameters, map);
} catch (std::exception & e) {
Expand Down
27 changes: 27 additions & 0 deletions nav2_map_server/test/unit/test_map_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -311,3 +311,30 @@ TEST_F(MapIOTester, loadInvalidYAML)
LoadParameters loadParameters;
ASSERT_ANY_THROW(loadParameters = loadMapYaml(path(TEST_DIR) / path("invalid_file.yaml")));
}

TEST(HomeUserExpanderTestSuite, homeUserExpanderShouldNotChangeInputStringWhenShorterThanTwo)
{
const std::string emptyFileName{};
ASSERT_EQ(emptyFileName, expand_user_home_dir_if_needed(emptyFileName, "/home/user"));
}

TEST(
HomeUserExpanderTestSuite,
homeUserExpanderShouldNotChangeInputStringWhenInputStringDoesNotStartWithHomeSequence)
{
const std::string fileName{"valid_file.yaml"};
ASSERT_EQ(fileName, expand_user_home_dir_if_needed(fileName, "/home/user"));
}

TEST(HomeUserExpanderTestSuite, homeUserExpanderShouldNotChangeInputStringWhenHomeVariableNotFound)
{
const std::string fileName{"~/valid_file.yaml"};
ASSERT_EQ(fileName, expand_user_home_dir_if_needed(fileName, ""));
}

TEST(HomeUserExpanderTestSuite, homeUserExpanderShouldExpandHomeSequenceWhenHomeVariableSet)
{
const std::string fileName{"~/valid_file.yaml"};
const std::string expectedOutputFileName{"/home/user/valid_file.yaml"};
ASSERT_EQ(expectedOutputFileName, expand_user_home_dir_if_needed(fileName, "/home/user"));
}

0 comments on commit 61a774b

Please sign in to comment.