|
38 | 38 | from launch import LaunchDescription |
39 | 39 | from launch.actions import DeclareLaunchArgument, OpaqueFunction |
40 | 40 | from launch.conditions import IfCondition |
41 | | -from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution |
| 41 | +from launch.substitutions import ( |
| 42 | + Command, |
| 43 | + FindExecutable, |
| 44 | + LaunchConfiguration, |
| 45 | + PathJoinSubstitution, |
| 46 | + OrSubstitution, |
| 47 | +) |
42 | 48 |
|
43 | 49 |
|
44 | 50 | def launch_setup(context, *args, **kwargs): |
@@ -173,7 +179,9 @@ def launch_setup(context, *args, **kwargs): |
173 | 179 | # Trajectory Execution Configuration |
174 | 180 | controllers_yaml = load_yaml("ur_moveit_config", "config/controllers.yaml") |
175 | 181 | # the scaled_joint_trajectory_controller does not work on fake hardware |
176 | | - change_controllers = context.perform_substitution(use_fake_hardware) |
| 182 | + change_controllers = context.perform_substitution( |
| 183 | + OrSubstitution(use_fake_hardware, use_sim_time) |
| 184 | + ) |
177 | 185 | if change_controllers == "true": |
178 | 186 | controllers_yaml["scaled_joint_trajectory_controller"]["default"] = False |
179 | 187 | controllers_yaml["joint_trajectory_controller"]["default"] = True |
@@ -242,6 +250,9 @@ def launch_setup(context, *args, **kwargs): |
242 | 250 | robot_description_kinematics, |
243 | 251 | robot_description_planning, |
244 | 252 | warehouse_ros_config, |
| 253 | + { |
| 254 | + "use_sim_time": use_sim_time, |
| 255 | + }, |
245 | 256 | ], |
246 | 257 | ) |
247 | 258 |
|
|
0 commit comments