Skip to content

Commit

Permalink
Update declare parameters
Browse files Browse the repository at this point in the history
Signed-off-by: Barış Zeren <[email protected]>
  • Loading branch information
StepTurtle authored and mehmetdogru committed Feb 27, 2024
1 parent e8d80c0 commit 1275f6f
Showing 1 changed file with 6 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -83,15 +83,16 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
declare_parameter("lanelet2_map_path", "");
declare_parameter("center_line_resolution");

std::vector<std::string> tmp_lanelet2_paths_or_directory =
declare_parameter<std::vector<std::string>>("lanelet2_map_folder_path");
std::string tmp_lanelet2_map_metadata_path =
declare_parameter<std::string>("lanelet2_map_metadata_path");
if (declare_parameter<bool>("enabled_dynamic_lanelet_loading")) {
std::vector<std::string> lanelet2_paths_or_directory =
declare_parameter<std::vector<std::string>>("lanelet2_map_folder_path");
std::string lanelet2_map_metadata_path =
declare_parameter<std::string>("lanelet2_map_metadata_path");

std::map<std::string, Lanelet2FileMetaData> lanelet2_metadata_dict;
try {
lanelet2_metadata_dict = getLanelet2Metadata(
tmp_lanelet2_map_metadata_path, getLanelet2Paths(tmp_lanelet2_paths_or_directory));
lanelet2_map_metadata_path, getLanelet2Paths(lanelet2_paths_or_directory));
} catch (std::runtime_error & e) {
RCLCPP_ERROR_STREAM(get_logger(), "Failed to load lanelet2 metadata");
}
Expand Down

0 comments on commit 1275f6f

Please sign in to comment.