Skip to content

Commit 82590df

Browse files
Improve launchfile
* Add ability to modify the node parameters from the launchscript * Add ability to change the topic that we publish the pose estimates
1 parent bc29e07 commit 82590df

2 files changed

Lines changed: 61 additions & 6 deletions

File tree

Lines changed: 60 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,73 @@
11
from launch import LaunchDescription
22
import launch.substitutions
33
import launch_ros.actions
4+
import launch.condition
45

56

67
def generate_launch_description():
7-
use_sim_time = launch.substitutions.LaunchConfiguration('use_sim_time', default='false')
8+
config_vars = [["use_sim_time", 'false'],
9+
["maxUrange", '80.0'],
10+
["maxRange", '0.0'],
11+
["minimum_score", '0'],
12+
["sigma", '0.05'],
13+
["kernelSize", '1'],
14+
["lstep", '0.05'],
15+
["astep", '0.05'],
16+
["iterations", '5'],
17+
["lsigma", '0.075'],
18+
["ogain", '3.0'],
19+
["lskip", '0'],
20+
["srr", '0.1'],
21+
["srt", '0.2'],
22+
["str", '0.1'],
23+
["stt", '0.2'],
24+
["linearUpdate", '1.0'],
25+
["angularUpdate", '0.5'],
26+
["temporalUpdate", '1.0'],
27+
["resampleThreshold", '0.5'],
28+
["particles", '30'],
29+
["xmin", '-10.0'],
30+
["ymin", '-10.0'],
31+
["xmax", '10.0'],
32+
["ymax", '10.0'],
33+
["delta", '0.05'],
34+
["occ_thresh", '0.25'],
35+
["llsamplerange", '0.01'],
36+
["llsamplestep", '0.01'],
37+
["lasamplerange", '0.005'],
38+
["lasamplestep", '0.005'],
39+
]
840

9-
return LaunchDescription([
10-
launch.actions.DeclareLaunchArgument(
11-
'use_sim_time', default_value='false', description='Use simulation clock if true'),
1241

42+
launch_args = [
43+
launch.actions.DeclareLaunchArgument(
44+
name=k,
45+
default_value=v,
46+
description="Modify the [{}] gmapping parameter".format(k))
47+
for k, v in config_vars ]
48+
return LaunchDescription([
49+
*launch_args,
50+
launch.actions.DeclareLaunchArgument(name="pose_topic",
51+
default_value="/pose"),
1352
launch_ros.actions.Node(
1453
package='slam_gmapping',
1554
node_executable='slam_gmapping',
1655
node_name='slam_gmapping', output='screen',
17-
parameters=[{ 'use_sim_time': use_sim_time}, ]),
56+
parameters=[{k: launch.substitutions.LaunchConfiguration(k)
57+
for k, _ in config_vars }],
58+
remappings=[("/pose",
59+
launch.substitutions.LaunchConfiguration("pose_topic"))]
60+
),
1861
])
62+
63+
64+
# launch.actions.DeclareLaunchArgument(
65+
# 'maxUrange', default_value='false', description='Use simulation (Gazebo) clock if true'),
66+
67+
# return LaunchDescription([
68+
# launch_ros.actions.Node(
69+
# package='slam_gmapping',
70+
# node_executable='slam_gmapping',
71+
# node_name='slam_gmapping', output='screen',
72+
# parameters=[{'maxUrange': maxUrange}]),
73+
# ])

slam_gmapping/src/slam_gmapping.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,7 @@ std::error_code SlamGmapping::initParameters()
107107
xmax_ = parameters_client_->get_parameter("xmax", 10.0);
108108
ymax_ = parameters_client_->get_parameter("ymax", 10.0);
109109
delta_ = parameters_client_->get_parameter("delta", 0.05);
110-
occ_thresh_ = parameters_client_->get_parameter("occ", 0.25);
110+
occ_thresh_ = parameters_client_->get_parameter("occ_thresh", 0.25);
111111
llsamplerange_ = parameters_client_->get_parameter("llsamplerange", 0.01);
112112
llsamplestep_ = parameters_client_->get_parameter("llsamplestep", 0.01);
113113
lasamplerange_ = parameters_client_->get_parameter("lasamplerange", 0.005);

0 commit comments

Comments
 (0)