Skip to content
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

fix(lanelet2_map_loader): fixed parameter declaration timing #4639

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -57,13 +57,16 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
adaptor.init_sub(
sub_map_projector_type_,
[this](const MapProjectorInfo::Message::ConstSharedPtr msg) { on_map_projector_info(msg); });

declare_parameter("lanelet2_map_path", "");
declare_parameter("center_line_resolution", 5.0);
}

void Lanelet2MapLoaderNode::on_map_projector_info(
const MapProjectorInfo::Message::ConstSharedPtr msg)
{
const auto lanelet2_filename = declare_parameter("lanelet2_map_path", "");
const auto center_line_resolution = declare_parameter("center_line_resolution", 5.0);
const auto lanelet2_filename = get_parameter("lanelet2_map_path").as_string();
const auto center_line_resolution = get_parameter("center_line_resolution").as_double();

// load map from file
const auto map =
Expand Down