Skip to content

Commit 6f34357

Browse files
SteveMacenskijames-wardJames Wardgene-su
authored
Sync Humble Sept 25 (#637)
* Optional map saver (#633) * Add parameter to stop map saver from being initialised Map saver will subscribe to the map topic and force updates of the map even when nothing else is subscribed. This allows it to be turned off to save processing cycles. * Add details of use_map_saver parameter to README * Add defaulted-true use_map_saver parameter to launch configs --------- Co-authored-by: James Ward <[email protected]> * adding namespace support for map saving (#613) * fix mismatched service name in rviz plugin (#634) * bumping to 2.6.6 for release --------- Co-authored-by: James Ward <[email protected]> Co-authored-by: James Ward <[email protected]> Co-authored-by: gene.su <[email protected]>
1 parent 72b6f61 commit 6f34357

10 files changed

+25
-7
lines changed

README.md

+2
Original file line numberDiff line numberDiff line change
@@ -224,6 +224,8 @@ The following settings and options are exposed to you. My default configuration
224224

225225
`scan_queue_size` - The number of scan messages to queue up before throwing away old ones. Should always be set to 1 in async mode
226226

227+
`use_map_saver` - Instantiate the map saver service and self-subscribe to the map topic
228+
227229
`map_file_name` - Name of the pose-graph file to load on startup if available
228230

229231
`map_start_pose` - Pose to start pose-graph mapping/localization in, if available

config/mapper_params_lifelong.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@ slam_toolbox:
1515
map_frame: map
1616
base_frame: base_footprint
1717
scan_topic: /scan
18+
use_map_saver: true
1819
mode: mapping
1920

2021
# lifelong params

config/mapper_params_offline.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@ slam_toolbox:
1414
map_frame: map
1515
base_frame: base_footprint
1616
scan_topic: /scan
17+
use_map_saver: true
1718
mode: mapping #localization
1819
debug_logging: false
1920
throttle_scans: 1

config/mapper_params_online_async.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@ slam_toolbox:
1414
map_frame: map
1515
base_frame: base_footprint
1616
scan_topic: /scan
17+
use_map_saver: true
1718
mode: mapping #localization
1819

1920
# if you'd like to immediately start continuing a map at a given pose

config/mapper_params_online_sync.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@ slam_toolbox:
1414
map_frame: map
1515
base_frame: base_footprint
1616
scan_topic: /scan
17+
use_map_saver: true
1718
mode: mapping #localization
1819

1920
# if you'd like to immediately start continuing a map at a given pose

include/slam_toolbox/slam_toolbox_common.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -142,6 +142,7 @@ class SlamToolbox : public rclcpp::Node
142142

143143
// Storage for ROS parameters
144144
std::string odom_frame_, map_frame_, base_frame_, map_name_, scan_topic_;
145+
bool use_map_saver_;
145146
rclcpp::Duration transform_timeout_, minimum_time_interval_;
146147
std_msgs::msg::Header scan_header;
147148
int throttle_scans_, scan_queue_size_;

package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>slam_toolbox</name>
5-
<version>2.6.5</version>
5+
<version>2.6.6</version>
66
<description>
77
This package provides a sped up improved slam karto with updated SDK and visualization and modification toolsets
88
</description>

rviz_plugin/slam_toolbox_rviz_plugin.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -78,9 +78,9 @@ SlamToolboxPlugin::SlamToolboxPlugin(QWidget * parent)
7878
"/slam_toolbox/pause_new_measurements");
7979
_load_submap_for_merging =
8080
ros_node_->create_client<slam_toolbox::srv::AddSubmap>(
81-
"/map_merging/add_submap");
81+
"/slam_toolbox/add_submap");
8282
_merge = ros_node_->create_client<slam_toolbox::srv::MergeMaps>(
83-
"/map_merging/merge_submaps");
83+
"/slam_toolbox/merge_submaps");
8484

8585
_vbox = new QVBoxLayout();
8686
_hbox1 = new QHBoxLayout();

src/map_saver.cpp

+8-2
Original file line numberDiff line numberDiff line change
@@ -58,10 +58,16 @@ bool MapSaver::saveMapCallback(
5858
}
5959

6060
const std::string name = req->name.data;
61+
std::string set_namespace;
62+
const std::string namespace_str = std::string(node_->get_namespace());
63+
if (!namespace_str.empty()) {
64+
set_namespace = " -r __ns:=" + namespace_str;
65+
}
66+
6167
if (name != "") {
6268
RCLCPP_INFO(node_->get_logger(),
6369
"SlamToolbox: Saving map as %s.", name.c_str());
64-
int rc = system(("ros2 run nav2_map_server map_saver_cli -f " + name + " --ros-args -p map_subscribe_transient_local:=true").c_str());
70+
int rc = system(("ros2 run nav2_map_server map_saver_cli -f " + name + " --ros-args -p map_subscribe_transient_local:=true" + set_namespace).c_str());
6571
if (rc == 0) {
6672
response->result = response->RESULT_SUCCESS;
6773
} else {
@@ -70,7 +76,7 @@ bool MapSaver::saveMapCallback(
7076
} else {
7177
RCLCPP_INFO(node_->get_logger(),
7278
"SlamToolbox: Saving map in current directory.");
73-
int rc = system("ros2 run nav2_map_server map_saver_cli --ros-args -p map_subscribe_transient_local:=true");
79+
int rc = system(("ros2 run nav2_map_server map_saver_cli --ros-args -p map_subscribe_transient_local:=true" + set_namespace).c_str());
7480
if (rc == 0) {
7581
response->result = response->RESULT_SUCCESS;
7682
} else {

src/slam_toolbox_common.cpp

+7-2
Original file line numberDiff line numberDiff line change
@@ -61,8 +61,10 @@ void SlamToolbox::configure()
6161
pose_helper_ = std::make_unique<pose_utils::GetPoseHelper>(
6262
tf_.get(), base_frame_, odom_frame_);
6363
scan_holder_ = std::make_unique<laser_utils::ScanHolder>(lasers_);
64-
map_saver_ = std::make_unique<map_saver::MapSaver>(shared_from_this(),
65-
map_name_);
64+
if (use_map_saver_) {
65+
map_saver_ = std::make_unique<map_saver::MapSaver>(shared_from_this(),
66+
map_name_);
67+
}
6668
closure_assistant_ =
6769
std::make_unique<loop_closure_assistant::LoopClosureAssistant>(
6870
shared_from_this(), smapper_->getMapper(), scan_holder_.get(),
@@ -144,6 +146,9 @@ void SlamToolbox::setParams()
144146
map_name_ = std::string("/map");
145147
map_name_ = this->declare_parameter("map_name", map_name_);
146148

149+
use_map_saver_ = true;
150+
use_map_saver_ = this->declare_parameter("use_map_saver", use_map_saver_);
151+
147152
scan_topic_ = std::string("/scan");
148153
scan_topic_ = this->declare_parameter("scan_topic", scan_topic_);
149154

0 commit comments

Comments
 (0)