Skip to content
Merged
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
34 changes: 10 additions & 24 deletions moveit_demo_nodes/run_move_group/launch/run_move_group.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -157,30 +157,16 @@ def generate_launch_description():
},
)

# load joint_state_controller
load_joint_state_controller = ExecuteProcess(
cmd=["ros2 control load_start_controller joint_state_controller"],
shell=True,
output="screen",
)
load_controllers = [load_joint_state_controller]
# load panda_arm_controller
load_controllers += [
ExecuteProcess(
cmd=["ros2 control load_configure_controller panda_arm_controller"],
shell=True,
output="screen",
on_exit=[
ExecuteProcess(
cmd=[
"ros2 control switch_controllers --start-controllers panda_arm_controller"
],
shell=True,
output="screen",
)
],
)
]
# Load controllers
load_controllers = []
for controller in ["panda_arm_controller", "joint_state_controller"]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner.py {}".format(controller)],
shell=True,
output="screen",
)
]

# Warehouse mongodb server
mongodb_server_node = Node(
Expand Down
34 changes: 10 additions & 24 deletions moveit_demo_nodes/run_moveit_cpp/launch/run_moveit_cpp.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -142,30 +142,16 @@ def generate_launch_description():
},
)

# load joint_state_controller
load_joint_state_controller = ExecuteProcess(
cmd=["ros2 control load_start_controller joint_state_controller"],
shell=True,
output="screen",
)
load_controllers = [load_joint_state_controller]
# load panda_arm_controller
load_controllers += [
ExecuteProcess(
cmd=["ros2 control load_configure_controller panda_arm_controller"],
shell=True,
output="screen",
on_exit=[
ExecuteProcess(
cmd=[
"ros2 control switch_controllers --start-controllers panda_arm_controller"
],
shell=True,
output="screen",
)
],
)
]
# Load controllers
load_controllers = []
for controller in ["panda_arm_controller", "joint_state_controller"]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner.py {}".format(controller)],
shell=True,
output="screen",
)
]

return LaunchDescription(
[
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -158,30 +158,16 @@ def generate_launch_description():
},
)

# load joint_state_controller
load_joint_state_controller = ExecuteProcess(
cmd=["ros2 control load_start_controller joint_state_controller"],
shell=True,
output="screen",
)
load_controllers = [load_joint_state_controller]
# load panda_arm_controller
load_controllers += [
ExecuteProcess(
cmd=["ros2 control load_configure_controller panda_arm_controller"],
shell=True,
output="screen",
on_exit=[
ExecuteProcess(
cmd=[
"ros2 control switch_controllers --start-controllers panda_arm_controller"
],
shell=True,
output="screen",
)
],
)
]
# Load controllers
load_controllers = []
for controller in ["panda_arm_controller", "joint_state_controller"]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner.py {}".format(controller)],
shell=True,
output="screen",
)
]

# Warehouse mongodb server
mongodb_server_node = Node(
Expand Down
34 changes: 10 additions & 24 deletions moveit_ros/moveit_servo/launch/pose_tracking_example.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -123,30 +123,16 @@ def generate_launch_description():
},
)

# load joint_state_controller
load_joint_state_controller = ExecuteProcess(
cmd=["ros2 control load_start_controller joint_state_controller"],
shell=True,
output="screen",
)
load_controllers = [load_joint_state_controller]
# load panda_arm_controller
load_controllers += [
ExecuteProcess(
cmd=["ros2 control load_configure_controller panda_arm_controller"],
shell=True,
output="screen",
on_exit=[
ExecuteProcess(
cmd=[
"ros2 control switch_controllers --start-controllers panda_arm_controller"
],
shell=True,
output="screen",
)
],
)
]
# Load controllers
load_controllers = []
for controller in ["panda_arm_controller", "joint_state_controller"]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner.py {}".format(controller)],
shell=True,
output="screen",
)
]

return LaunchDescription(
[
Expand Down
34 changes: 10 additions & 24 deletions moveit_ros/moveit_servo/launch/servo_cpp_interface_demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -108,30 +108,16 @@ def generate_launch_description():
},
)

# load joint_state_controller
load_joint_state_controller = ExecuteProcess(
cmd=["ros2 control load_start_controller joint_state_controller"],
shell=True,
output="screen",
)
load_controllers = [load_joint_state_controller]
# load panda_arm_controller
load_controllers += [
ExecuteProcess(
cmd=["ros2 control load_configure_controller panda_arm_controller"],
shell=True,
output="screen",
on_exit=[
ExecuteProcess(
cmd=[
"ros2 control switch_controllers --start-controllers panda_arm_controller"
],
shell=True,
output="screen",
)
],
)
]
# Load controllers
load_controllers = []
for controller in ["panda_arm_controller", "joint_state_controller"]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner.py {}".format(controller)],
shell=True,
output="screen",
)
]

return LaunchDescription(
[rviz_node, static_tf, servo_node, ros2_control_node, robot_state_publisher]
Expand Down
34 changes: 10 additions & 24 deletions moveit_ros/moveit_servo/launch/servo_server_demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,30 +84,16 @@ def generate_launch_description():
},
)

# load joint_state_controller
load_joint_state_controller = ExecuteProcess(
cmd=["ros2 control load_start_controller joint_state_controller"],
shell=True,
output="screen",
)
load_controllers = [load_joint_state_controller]
# load panda_arm_controller
load_controllers += [
ExecuteProcess(
cmd=["ros2 control load_configure_controller panda_arm_controller"],
shell=True,
output="screen",
on_exit=[
ExecuteProcess(
cmd=[
"ros2 control switch_controllers --start-controllers panda_arm_controller"
],
shell=True,
output="screen",
)
],
)
]
# Load controllers
load_controllers = []
for controller in ["panda_arm_controller", "joint_state_controller"]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner.py {}".format(controller)],
shell=True,
output="screen",
)
]

# Launch as much as possible in components
container = ComposableNodeContainer(
Expand Down
34 changes: 10 additions & 24 deletions moveit_ros/moveit_servo/launch/servo_teleop.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -82,30 +82,16 @@ def generate_launch_description():
},
)

# load joint_state_controller
load_joint_state_controller = ExecuteProcess(
cmd=["ros2 control load_start_controller joint_state_controller"],
shell=True,
output="screen",
)
load_controllers = [load_joint_state_controller]
# load panda_arm_controller
load_controllers += [
ExecuteProcess(
cmd=["ros2 control load_configure_controller panda_arm_controller"],
shell=True,
output="screen",
on_exit=[
ExecuteProcess(
cmd=[
"ros2 control switch_controllers --start-controllers panda_arm_controller"
],
shell=True,
output="screen",
)
],
)
]
# Load controllers
load_controllers = []
for controller in ["panda_arm_controller", "joint_state_controller"]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner.py {}".format(controller)],
shell=True,
output="screen",
)
]

# Launch as much as possible in components
container = ComposableNodeContainer(
Expand Down
38 changes: 12 additions & 26 deletions moveit_ros/moveit_servo/test/launch/servo_launch_test_common.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
from launch_ros.actions import ComposableNodeContainer, Node
from launch_ros.descriptions import ComposableNode
from ament_index_python.packages import get_package_share_directory
from launch.actions import ExecuteProcess
from launch.actions import ExecuteProcess, TimerAction
import xacro


Expand Down Expand Up @@ -92,30 +92,16 @@ def generate_servo_test_description(
},
)

# load joint_state_controller
load_joint_state_controller = ExecuteProcess(
cmd=["ros2 control load_start_controller joint_state_controller"],
shell=True,
output="screen",
)
load_controllers = [load_joint_state_controller]
# load panda_arm_controller
load_controllers += [
ExecuteProcess(
cmd=["ros2 control load_configure_controller panda_arm_controller"],
shell=True,
output="screen",
on_exit=[
ExecuteProcess(
cmd=[
"ros2 control switch_controllers --start-controllers panda_arm_controller"
],
shell=True,
output="screen",
)
],
)
]
# Load controllers
load_controllers = []
for controller in ["panda_arm_controller", "joint_state_controller"]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner.py {}".format(controller)],
shell=True,
output="screen",
)
]

# Component nodes for tf and Servo
test_container = ComposableNodeContainer(
Expand Down Expand Up @@ -170,7 +156,7 @@ def generate_servo_test_description(
),
ros2_control_node,
test_container,
servo_gtest,
TimerAction(period=2.0, actions=[servo_gtest]),
launch_testing.actions.ReadyToTest(),
]
+ load_controllers
Expand Down
Loading