|
1 | 1 | from launch import LaunchDescription |
2 | 2 | import launch.substitutions |
3 | 3 | import launch_ros.actions |
| 4 | +import launch.condition |
4 | 5 |
|
5 | 6 |
|
6 | 7 | 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 | + ] |
8 | 40 |
|
9 | | - return LaunchDescription([ |
10 | | - launch.actions.DeclareLaunchArgument( |
11 | | - 'use_sim_time', default_value='false', description='Use simulation clock if true'), |
12 | 41 |
|
| 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"), |
13 | 52 | launch_ros.actions.Node( |
14 | 53 | package='slam_gmapping', |
15 | 54 | node_executable='slam_gmapping', |
16 | 55 | 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 | + ), |
18 | 61 | ]) |
| 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 | + # ]) |
0 commit comments