Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Revert spawner reordering #547

Draft
wants to merge 2 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 6 additions & 7 deletions example_1/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -105,21 +105,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
21 changes: 7 additions & 14 deletions example_10/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,27 +93,20 @@ def generate_launch_description():
arguments=["gpio_controller", "--param-file", robot_controllers],
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_gpio_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[gpio_controller_spawner],
)
)
delay_joint_state_broadcaster_after_gpio_controller_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=gpio_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
delay_gpio_after_robot_controller_spawner,
delay_joint_state_broadcaster_after_gpio_controller_spawner,
joint_state_broadcaster_spawner,
gpio_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
13 changes: 6 additions & 7 deletions example_11/bringup/launch/carlikebot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -125,22 +125,21 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_bicycle_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_bicycle_controller_spawner],
)
)

nodes = [
control_node,
control_node_remapped,
robot_state_pub_bicycle_node,
robot_bicycle_controller_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
14 changes: 6 additions & 8 deletions example_12/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -111,22 +111,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=j1_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[j1_controller_spawner, j2_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
j1_controller_spawner,
j2_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
Original file line number Diff line number Diff line change
Expand Up @@ -134,21 +134,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
2 changes: 1 addition & 1 deletion example_15/bringup/launch/rrbot_base.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -229,9 +229,9 @@ def generate_launch_description():
nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
robot_controller_spawner,
]

return LaunchDescription(declared_arguments + nodes)
2 changes: 1 addition & 1 deletion example_15/bringup/launch/rrbot_namespace.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -134,9 +134,9 @@ def generate_launch_description():
nodes = [
control_node,
robot_state_pub_node,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
robot_forward_position_controller_spawner,
joint_state_broadcaster_spawner,
robot_position_trajectory_controller_spawner,
]

Expand Down
13 changes: 6 additions & 7 deletions example_2/bringup/launch/diffbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -114,21 +114,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
13 changes: 6 additions & 7 deletions example_3/bringup/launch/rrbot_system_multi_interface.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -157,21 +157,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
13 changes: 6 additions & 7 deletions example_4/bringup/launch/rrbot_system_with_sensor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -156,21 +156,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
fts_broadcaster_spawner,
]

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -156,21 +156,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
fts_broadcaster_spawner,
]

Expand Down
13 changes: 6 additions & 7 deletions example_6/bringup/launch/rrbot_modular_actuators.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -157,21 +157,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
13 changes: 6 additions & 7 deletions example_7/bringup/launch/r6bot_controller.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -102,21 +102,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
Original file line number Diff line number Diff line change
Expand Up @@ -134,21 +134,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
13 changes: 6 additions & 7 deletions example_9/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -106,21 +106,20 @@ def generate_launch_description():
)
)

# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
robot_controller_spawner,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
Loading