Skip to content

Commit 9c33a93

Browse files
author
Felix Exner (fexner)
authored
[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.
1 parent 28766bf commit 9c33a93

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):
@@ -167,7 +173,9 @@ def launch_setup(context, *args, **kwargs):
167173
# Trajectory Execution Configuration
168174
controllers_yaml = load_yaml("ur_moveit_config", "config/controllers.yaml")
169175
# the scaled_joint_trajectory_controller does not work on fake hardware
170-
change_controllers = context.perform_substitution(use_fake_hardware)
176+
change_controllers = context.perform_substitution(
177+
OrSubstitution(use_fake_hardware, use_sim_time)
178+
)
171179
if change_controllers == "true":
172180
controllers_yaml["scaled_joint_trajectory_controller"]["default"] = False
173181
controllers_yaml["joint_trajectory_controller"]["default"] = True
@@ -235,6 +243,9 @@ def launch_setup(context, *args, **kwargs):
235243
robot_description_kinematics,
236244
robot_description_planning,
237245
warehouse_ros_config,
246+
{
247+
"use_sim_time": use_sim_time,
248+
},
238249
],
239250
)
240251

0 commit comments

Comments
 (0)