There was an error while loading. Please reload this page.
1 parent 3e4a7a3 commit d91f0d5Copy full SHA for d91f0d5
nav2_bringup/launch/tb4_loopback_simulation_launch.py
@@ -141,6 +141,8 @@ def generate_launch_description() -> LaunchDescription:
141
'autostart': autostart,
142
'use_composition': use_composition,
143
'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
146
'use_localization': 'False', # Don't use SLAM, AMCL
147
}.items(),
148
)
@@ -158,8 +160,9 @@ def generate_launch_description() -> LaunchDescription:
158
160
package='tf2_ros',
159
161
executable='static_transform_publisher',
162
arguments=[
- '0.0', '0.0', '0.0', '0', '0', '0',
- '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']
166
167
168
configured_params = ParameterFile(
0 commit comments