11from launch import LaunchDescription
2+ from launch .actions import DeclareLaunchArgument
3+ from launch .substitutions import LaunchConfiguration
24from launch_ros .actions import Node
35from moveit_configs_utils import MoveItConfigsBuilder
46
@@ -7,21 +9,21 @@ def generate_launch_description():
79 moveit_config = (
810 MoveItConfigsBuilder ("moveit_resources_panda" )
911 .robot_description (file_path = "config/panda.urdf.xacro" )
10- .planning_pipelines (pipelines = ["ompl" ])
1112 .to_moveit_configs ()
1213 )
1314
14- cartesian_task = Node (
15+ node = Node (
1516 package = "moveit_task_constructor_demo" ,
16- executable = "alternative_path_costs" ,
17+ executable = LaunchConfiguration ( "exe" ) ,
1718 output = "screen" ,
1819 parameters = [
19- moveit_config .joint_limits ,
2020 moveit_config .robot_description ,
2121 moveit_config .robot_description_semantic ,
2222 moveit_config .robot_description_kinematics ,
23+ moveit_config .joint_limits ,
2324 moveit_config .planning_pipelines ,
2425 ],
2526 )
2627
27- return LaunchDescription ([cartesian_task ])
28+ arg = DeclareLaunchArgument (name = "exe" )
29+ return LaunchDescription ([arg , node ])
0 commit comments