|
19 | 19 | from launch.actions import RegisterEventHandler
|
20 | 20 | from launch.event_handlers import OnProcessExit
|
21 | 21 | from launch.launch_description_sources import PythonLaunchDescriptionSource
|
22 |
| - |
| 22 | +from launch import LaunchDescription |
| 23 | +from launch.actions import DeclareLaunchArgument |
| 24 | +from launch.substitutions import LaunchConfiguration |
23 | 25 | from launch.actions import ExecuteProcess, EmitEvent
|
24 | 26 | from launch.events import Shutdown
|
25 | 27 |
|
@@ -202,6 +204,11 @@ def competition_bridges(world_name):
|
202 | 204 | def spawn(sim_mode, world_name, models, robot=None):
|
203 | 205 | if type(models) != list:
|
204 | 206 | models = [models]
|
| 207 | + use_sim_time = LaunchConfiguration('use_sim_time', default='true') |
| 208 | + DeclareLaunchArgument( |
| 209 | + 'use_sim_time', |
| 210 | + default_value='true', |
| 211 | + description='Use simulation (Gazebo) clock if true'), |
205 | 212 |
|
206 | 213 | launch_processes = []
|
207 | 214 | for model in models:
|
@@ -237,13 +244,25 @@ def spawn(sim_mode, world_name, models, robot=None):
|
237 | 244 | remappings=[bridge.remapping() for bridge in bridges],
|
238 | 245 | ))
|
239 | 246 |
|
240 |
| - # tf broadcaster |
| 247 | + # tf broadcaster (sensors) |
241 | 248 | nodes.append(Node(
|
242 | 249 | package='vrx_ros',
|
243 | 250 | executable='pose_tf_broadcaster',
|
244 | 251 | output='screen',
|
245 | 252 | ))
|
246 | 253 |
|
| 254 | + # robot_state_publisher (tf for wamv) |
| 255 | + model_dir = os.path.join(get_package_share_directory('vrx_gazebo'), 'models/wamv/tmp') |
| 256 | + urdf_file = os.path.join(model_dir, 'model.urdf') |
| 257 | + with open(urdf_file, 'r') as infp: |
| 258 | + robot_desc = infp.read() |
| 259 | + params = {'use_sim_time': use_sim_time, 'frame_prefix': 'wamv/', 'robot_description': robot_desc} |
| 260 | + nodes.append(Node(package='robot_state_publisher', |
| 261 | + executable='robot_state_publisher', |
| 262 | + output='both', |
| 263 | + parameters=[params], |
| 264 | + remappings=[('/joint_states', '/wamv/joint_states')])) |
| 265 | + |
247 | 266 | group_action = GroupAction([
|
248 | 267 | PushRosNamespace(model.model_name),
|
249 | 268 | *nodes
|
|
0 commit comments