Skip to content
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
2 changes: 1 addition & 1 deletion nav2_map_server/include/nav2_map_server/map_saver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,6 @@ class MapSaver : public nav2_util::LifecycleNode
const std::string & map_topic,
const SaveParameters & save_parameters);

protected:
/**
* @brief Sets up map saving service
* @param state Lifecycle Node's state
Expand Down Expand Up @@ -88,6 +87,7 @@ class MapSaver : public nav2_util::LifecycleNode
*/
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;

protected:
/**
* @brief Map saving service callback
* @param request_header Service request header
Expand Down
1 change: 1 addition & 0 deletions nav2_map_server/src/map_saver/main_cli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,6 +164,7 @@ int main(int argc, char ** argv)
int retcode;
try {
auto map_saver = std::make_shared<nav2_map_server::MapSaver>();
map_saver->on_configure(rclcpp_lifecycle::State());
if (map_saver->saveMapTopicToFile(map_topic, save_parameters)) {
retcode = 0;
} else {
Expand Down
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();
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