Skip to content

Commit

Permalink
Fixed pointed out issues
Browse files Browse the repository at this point in the history
Signed-off-by: TaikiYamada4 <[email protected]>
  • Loading branch information
TaikiYamada4 committed Oct 25, 2024
1 parent ef2f5ad commit b72177d
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 7 deletions.
8 changes: 4 additions & 4 deletions map/autoware_lanelet2_map_validator/src/lib/cli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ MetaConfig parseCommandLine(int argc, const char * argv[])
auto & validation_config = config.command_line_config.validationConfig;
po::options_description desc(
"Runs a set of validators on a map. Think of it like a linter. The following checks are "
"available:");
desc.add_options()("help,h", "this help message")
"available");
desc.add_options()("help,h", "This help message")

("map_file,m", po::value<std::string>(), "Path to the map to be validated")

Expand Down Expand Up @@ -60,14 +60,14 @@ MetaConfig parseCommandLine(int argc, const char * argv[])
("lat",
po::value(&validation_config.origin.lat)
->default_value(validation_config.origin.lat),
"latitude coordinate of map origin. This is required for the transverse "
"Latitude coordinate of map origin. This is required for the transverse "
"mercator "
"and utm projector.")

("lon",
po::value(&validation_config.origin.lon)
->default_value(validation_config.origin.lon),
"longitude coordinate of map origin. This is required for the transverse "
"Longitude coordinate of map origin. This is required for the transverse "
"mercator "
"and utm projector.")

Expand Down
8 changes: 5 additions & 3 deletions map/autoware_lanelet2_map_validator/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include <nlohmann/json.hpp>

#include <filesystem>
#include <fstream>
#include <iomanip>

Expand Down Expand Up @@ -120,10 +121,11 @@ int process_requirements(
}

if (!validator_config.output_file_path.empty()) {
std::string file_name = validator_config.output_file_path + "/lanelet2_validation_results.json";
std::ofstream output_file(file_name);
std::filesystem::path file_directory = validator_config.output_file_path;
std::filesystem::path file_path = file_directory / "lanelet2_validation_results.json";
std::ofstream output_file(file_path);
output_file << std::setw(4) << json_config;
std::cout << "Results are output to " << file_name << std::endl;
std::cout << "Results are output to " << file_path << std::endl;
}

return (warning_count + error_count == 0) ? 0 : 1;
Expand Down

0 comments on commit b72177d

Please sign in to comment.