Skip to content

Commit d91f0d5

Browse files
fixing loopback sim (#5384)
Signed-off-by: SteveMacenski <stevenmacenski@gmail.com>
1 parent 3e4a7a3 commit d91f0d5

File tree

1 file changed

+5
-2
lines changed

1 file changed

+5
-2
lines changed

‎nav2_bringup/launch/tb4_loopback_simulation_launch.py‎

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -141,6 +141,8 @@ def generate_launch_description() -> LaunchDescription:
141141
'autostart': autostart,
142142
'use_composition': use_composition,
143143
'use_respawn': use_respawn,
144+
'use_keepout_zones': 'False', # Keepout zones not used in loopback simulation
145+
'use_speed_zones': 'False', # Speed zones not used in loopback simulation
144146
'use_localization': 'False', # Don't use SLAM, AMCL
145147
}.items(),
146148
)
@@ -158,8 +160,9 @@ def generate_launch_description() -> LaunchDescription:
158160
package='tf2_ros',
159161
executable='static_transform_publisher',
160162
arguments=[
161-
'0.0', '0.0', '0.0', '0', '0', '0',
162-
'base_footprint', 'base_link']
163+
'--x', '0.0', '--y', '0.0', '--z', '0.0',
164+
'--roll', '0', '--pitch', '0', '--yaw', '0',
165+
'--frame-id', 'base_footprint', '--child-frame-id', 'base_link']
163166
)
164167

165168
configured_params = ParameterFile(

0 commit comments

Comments
 (0)