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

Get parameters on configure transition addressing #2985 #3000

Merged
merged 3 commits into from
Jun 9, 2022
Merged
Changes from 2 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
17 changes: 11 additions & 6 deletions nav2_map_server/src/map_saver/map_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,11 @@ MapSaver::MapSaver(const rclcpp::NodeOptions & options)
{
RCLCPP_INFO(get_logger(), "Creating");

save_map_timeout_ = std::make_shared<rclcpp::Duration>(
rclcpp::Duration::from_seconds(declare_parameter("save_map_timeout", 2.0)));

free_thresh_default_ = declare_parameter("free_thresh_default", 0.25),
occupied_thresh_default_ = declare_parameter("occupied_thresh_default", 0.65);
map_subscribe_transient_local_ = declare_parameter("map_subscribe_transient_local", true);
// Declare the node parameters
declare_parameter("save_map_timeout", 2.0);
declare_parameter("free_thresh_default", 0.25);
declare_parameter("occupied_thresh_default", 0.65);
declare_parameter("map_subscribe_transient_local", true);
}

MapSaver::~MapSaver()
Expand All @@ -66,6 +65,12 @@ MapSaver::on_configure(const rclcpp_lifecycle::State & /*state*/)
// Make name prefix for services
const std::string service_prefix = get_name() + std::string("/");

save_map_timeout_ = std::make_shared<rclcpp::Duration>(
rclcpp::Duration::from_seconds(get_parameter("save_map_timeout").as_double()));
free_thresh_default_ = get_parameter("free_thresh_default").as_double();
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
occupied_thresh_default_ = get_parameter("occupied_thresh_default").as_double();
map_subscribe_transient_local_ = get_parameter("map_subscribe_transient_local").as_bool();

// Create a service that saves the occupancy grid from map topic to a file
save_map_service_ = create_service<nav2_msgs::srv::SaveMap>(
service_prefix + save_map_service_name_,
Expand Down