From ea5f7bd209ac4e0192c185367f8825ce3af558e7 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 3 Oct 2024 14:28:50 +0200 Subject: [PATCH] Revert "another failure trial, the spawner wants to spawn a controller named """ This reverts commit f92255929ce124c389e14b6d2bc0e9d46ddcb8f9. --- ur_robot_driver/launch/ur_control.launch.py | 31 +++++++++++++++------ 1 file changed, 23 insertions(+), 8 deletions(-) diff --git a/ur_robot_driver/launch/ur_control.launch.py b/ur_robot_driver/launch/ur_control.launch.py index 0382b0484..c33344a7c 100644 --- a/ur_robot_driver/launch/ur_control.launch.py +++ b/ur_robot_driver/launch/ur_control.launch.py @@ -158,7 +158,7 @@ def controller_spawner(controllers, condition, active=True): controller_spawner_timeout, ] + inactive_flags - + controllers, + + [controllers], condition=condition, ) @@ -174,11 +174,26 @@ def controller_spawner(controllers, condition, active=True): "forward_velocity_controller", "forward_position_controller", ] - controllers_active_init = [*controllers_active_default, initial_joint_controller] - controllers_inactive_init = [ - PythonExpression(["'", c, "' if '", c, "' != '", initial_joint_controller, "' else ''"]) - for c in controllers_inactive_default - ] + controllers_active_init = PythonExpression( + [ + "'", + " ".join(controllers_active_default), + "' + ' ' +'", + initial_joint_controller, + "'", + ] + ) + controllers_inactive_init = PythonExpression( + [ + "' '.join([c for c in ", + str(controllers_inactive_default), + "if c != '", + initial_joint_controller, + "'])", + ] + ) + print(controllers_active_init.perform(context)) + print(controllers_inactive_init.perform(context)) controller_spawners = [ controller_spawner( @@ -190,11 +205,11 @@ def controller_spawner(controllers, condition, active=True): active=False, ), controller_spawner( - controllers_active_default, + " ".join(controllers_active_default), condition=UnlessCondition(activate_joint_controller), ), controller_spawner( - controllers_inactive_default, + " ".join(controllers_inactive_default), condition=UnlessCondition(activate_joint_controller), active=False, ),