Skip to content

Commit 42be491

Browse files
Felix Exner (fexner)mergify[bot]
authored andcommitted
[moveit] Properly handle use_sim_time (#1146)
Pass use_sim_time also to RViz and use non-scaled JTC when use_sim_time is active. (cherry picked from commit 9c33a93)
1 parent 255355d commit 42be491

File tree

1 file changed

+13
-2
lines changed

1 file changed

+13
-2
lines changed

ur_moveit_config/launch/ur_moveit.launch.py

Lines changed: 13 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,13 @@
3838
from launch import LaunchDescription
3939
from launch.actions import DeclareLaunchArgument, OpaqueFunction
4040
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+
)
4248

4349

4450
def launch_setup(context, *args, **kwargs):
@@ -173,7 +179,9 @@ def launch_setup(context, *args, **kwargs):
173179
# Trajectory Execution Configuration
174180
controllers_yaml = load_yaml("ur_moveit_config", "config/controllers.yaml")
175181
# 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+
)
177185
if change_controllers == "true":
178186
controllers_yaml["scaled_joint_trajectory_controller"]["default"] = False
179187
controllers_yaml["joint_trajectory_controller"]["default"] = True
@@ -242,6 +250,9 @@ def launch_setup(context, *args, **kwargs):
242250
robot_description_kinematics,
243251
robot_description_planning,
244252
warehouse_ros_config,
253+
{
254+
"use_sim_time": use_sim_time,
255+
},
245256
],
246257
)
247258

0 commit comments

Comments
 (0)