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

Optional transient map saver #2215

Merged
Show file tree
Hide file tree
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
1 change: 1 addition & 0 deletions nav2_bringup/bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -243,6 +243,7 @@ map_saver:
save_map_timeout: 5000
free_thresh_default: 0.25
occupied_thresh_default: 0.65
map_subscribe_transient_local: False

planner_server:
ros__parameters:
Expand Down
2 changes: 2 additions & 0 deletions nav2_map_server/include/nav2_map_server/map_saver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,8 @@ class MapSaver : public nav2_util::LifecycleNode
// Default values for map thresholds
double free_thresh_default_;
double occupied_thresh_default_;
// param for handling QoS configuration
bool map_subscribe_transient_local_;

// The name of the service for saving a map from topic
const std::string save_map_service_name_{"save_map"};
Expand Down
11 changes: 10 additions & 1 deletion nav2_map_server/src/map_saver/map_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,8 @@ MapSaver::MapSaver()

free_thresh_default_ = declare_parameter("free_thresh_default", 0.25),
occupied_thresh_default_ = declare_parameter("occupied_thresh_default", 0.65);
// false only of foxy for backwards compatibility
map_subscribe_transient_local_ = declare_parameter("map_subscribe_transient_local", false);
}

MapSaver::~MapSaver()
Expand Down Expand Up @@ -173,8 +175,15 @@ bool MapSaver::saveMapTopicToFile(
// Add new subscription for incoming map topic.
// Utilizing local rclcpp::Node (rclcpp_node_) from nav2_util::LifecycleNode
// as a map listener.
rclcpp::QoS map_qos = rclcpp::SystemDefaultsQoS(); // initialize to default
if (map_subscribe_transient_local_) {
map_qos = rclcpp::QoS(10);
map_qos.transient_local();
map_qos.reliable();
map_qos.keep_last(1);
}
auto map_sub = rclcpp_node_->create_subscription<nav_msgs::msg::OccupancyGrid>(
map_topic_loc, rclcpp::SystemDefaultsQoS(), mapCallback);
map_topic_loc, map_qos, mapCallback);

rclcpp::Time start_time = now();
while (rclcpp::ok()) {
Expand Down