Skip to content

Commit

Permalink
Revert "failure trial, because cannot pass all controllers as a singl…
Browse files Browse the repository at this point in the history
…e string separated with space"

This reverts commit 746b931.
  • Loading branch information
fmauch committed Oct 3, 2024
1 parent ea5f7bd commit 847002a
Showing 1 changed file with 9 additions and 43 deletions.
52 changes: 9 additions & 43 deletions ur_robot_driver/launch/ur_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@
LaunchConfiguration,
NotSubstitution,
PathJoinSubstitution,
PythonExpression,
)
from launch_ros.actions import Node
from launch_ros.parameter_descriptions import ParameterFile
Expand Down Expand Up @@ -146,7 +145,7 @@ def launch_setup(context):
)

# Spawn controllers
def controller_spawner(controllers, condition, active=True):
def controller_spawner(controllers, active=True):
inactive_flags = ["--inactive"] if not active else []
return Node(
package="controller_manager",
Expand All @@ -158,61 +157,28 @@ def controller_spawner(controllers, condition, active=True):
controller_spawner_timeout,
]
+ inactive_flags
+ [controllers],
condition=condition,
+ controllers,
)

controllers_active_default = [
controllers_active = [
"joint_state_broadcaster",
"io_and_status_controller",
"speed_scaling_state_broadcaster",
"force_torque_sensor_broadcaster",
]
controllers_inactive_default = [
controllers_inactive = [
"scaled_joint_trajectory_controller",
"joint_trajectory_controller",
"forward_velocity_controller",
"forward_position_controller",
]
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))
if activate_joint_controller.perform(context) == "true":
controllers_active.append(initial_joint_controller.perform(context))
controllers_inactive.remove(initial_joint_controller.perform(context))

controller_spawners = [
controller_spawner(
controllers_active_init, condition=IfCondition(activate_joint_controller)
),
controller_spawner(
controllers_inactive_init,
condition=IfCondition(activate_joint_controller),
active=False,
),
controller_spawner(
" ".join(controllers_active_default),
condition=UnlessCondition(activate_joint_controller),
),
controller_spawner(
" ".join(controllers_inactive_default),
condition=UnlessCondition(activate_joint_controller),
active=False,
),
controller_spawner(controllers_active),
controller_spawner(controllers_inactive, active=False),
]

rsp = IncludeLaunchDescription(
Expand Down

0 comments on commit 847002a

Please sign in to comment.