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

Nav Double Namespace fix #57

Merged
merged 1 commit into from
Oct 31, 2023
Merged
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
63 changes: 32 additions & 31 deletions turtlebot4_ignition_bringup/launch/turtlebot4_spawn.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -108,9 +108,6 @@ def generate_launch_description():
x, y, z = LaunchConfiguration('x'), LaunchConfiguration('y'), LaunchConfiguration('z')
yaw = LaunchConfiguration('yaw')
turtlebot4_node_yaml_file = LaunchConfiguration('param_file')
localization = LaunchConfiguration('localization')
slam = LaunchConfiguration('slam')
nav2 = LaunchConfiguration('nav2')

robot_name = GetNamespacedName(namespace, 'turtlebot4')
dock_name = GetNamespacedName(namespace, 'standard_dock')
Expand Down Expand Up @@ -238,36 +235,37 @@ def generate_launch_description():
]
),

# Localization
IncludeLaunchDescription(
PythonLaunchDescriptionSource([localization_launch]),
launch_arguments=[
('namespace', namespace),
('use_sim_time', use_sim_time)
],
condition=IfCondition(localization)
),
])

# SLAM
IncludeLaunchDescription(
PythonLaunchDescriptionSource([slam_launch]),
launch_arguments=[
('namespace', namespace),
('use_sim_time', use_sim_time)
],
condition=IfCondition(slam)
),
# Localization
localization = IncludeLaunchDescription(
PythonLaunchDescriptionSource([localization_launch]),
launch_arguments=[
('namespace', namespace),
('use_sim_time', use_sim_time)
],
condition=IfCondition(LaunchConfiguration('localization'))
)

# Nav2
IncludeLaunchDescription(
PythonLaunchDescriptionSource([nav2_launch]),
launch_arguments=[
('namespace', namespace),
('use_sim_time', use_sim_time)
],
condition=IfCondition(nav2)
),
])
# SLAM
slam = IncludeLaunchDescription(
PythonLaunchDescriptionSource([slam_launch]),
launch_arguments=[
('namespace', namespace),
('use_sim_time', use_sim_time)
],
condition=IfCondition(LaunchConfiguration('slam'))
)

# Nav2
nav2 = IncludeLaunchDescription(
PythonLaunchDescriptionSource([nav2_launch]),
launch_arguments=[
('namespace', namespace),
('use_sim_time', use_sim_time)
],
condition=IfCondition(LaunchConfiguration('nav2'))
)

# RViz
rviz = IncludeLaunchDescription(
Expand All @@ -282,5 +280,8 @@ def generate_launch_description():
ld = LaunchDescription(ARGUMENTS)
ld.add_action(param_file_cmd)
ld.add_action(spawn_robot_group_action)
ld.add_action(localization)
ld.add_action(slam)
ld.add_action(nav2)
ld.add_action(rviz)
return ld
Loading