mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
demo: replace individual launch files with common run.launch.py
Launch individual binaries with: ros2 launch moveit_task_constructor_demo run.launch.py exe:=<binary>
This commit is contained in:
parent
646a49f1fb
commit
bbc34d2b97
@ -1,25 +0,0 @@
|
|||||||
from launch import LaunchDescription
|
|
||||||
from launch_ros.actions import Node
|
|
||||||
from moveit_configs_utils import MoveItConfigsBuilder
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
|
||||||
moveit_config = (
|
|
||||||
MoveItConfigsBuilder("moveit_resources_panda")
|
|
||||||
.robot_description(file_path="config/panda.urdf.xacro")
|
|
||||||
.to_moveit_configs()
|
|
||||||
)
|
|
||||||
|
|
||||||
cartesian_task = Node(
|
|
||||||
package="moveit_task_constructor_demo",
|
|
||||||
executable="cartesian",
|
|
||||||
output="screen",
|
|
||||||
parameters=[
|
|
||||||
moveit_config.joint_limits,
|
|
||||||
moveit_config.robot_description,
|
|
||||||
moveit_config.robot_description_semantic,
|
|
||||||
moveit_config.robot_description_kinematics,
|
|
||||||
],
|
|
||||||
)
|
|
||||||
|
|
||||||
return LaunchDescription([cartesian_task])
|
|
||||||
@ -1,28 +0,0 @@
|
|||||||
from launch import LaunchDescription
|
|
||||||
from launch_ros.actions import Node
|
|
||||||
from moveit_configs_utils import MoveItConfigsBuilder
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
|
||||||
moveit_config = (
|
|
||||||
MoveItConfigsBuilder("moveit_resources_panda")
|
|
||||||
.robot_description(file_path="config/panda.urdf.xacro")
|
|
||||||
.planning_pipelines(pipelines=["ompl", "pilz_industrial_motion_planner"])
|
|
||||||
.to_moveit_configs()
|
|
||||||
)
|
|
||||||
|
|
||||||
fallbacks_move_to_task = Node(
|
|
||||||
package="moveit_task_constructor_demo",
|
|
||||||
executable="fallbacks_move_to",
|
|
||||||
output="screen",
|
|
||||||
parameters=[
|
|
||||||
moveit_config.pilz_cartesian_limits,
|
|
||||||
moveit_config.joint_limits,
|
|
||||||
moveit_config.planning_pipelines,
|
|
||||||
moveit_config.robot_description,
|
|
||||||
moveit_config.robot_description_kinematics,
|
|
||||||
moveit_config.robot_description_semantic,
|
|
||||||
],
|
|
||||||
)
|
|
||||||
|
|
||||||
return LaunchDescription([fallbacks_move_to_task])
|
|
||||||
@ -1,25 +0,0 @@
|
|||||||
from launch import LaunchDescription
|
|
||||||
from launch_ros.actions import Node
|
|
||||||
from moveit_configs_utils import MoveItConfigsBuilder
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
|
||||||
moveit_config = (
|
|
||||||
MoveItConfigsBuilder("moveit_resources_panda")
|
|
||||||
.robot_description(file_path="config/panda.urdf.xacro")
|
|
||||||
.to_moveit_configs()
|
|
||||||
)
|
|
||||||
|
|
||||||
cartesian_task = Node(
|
|
||||||
package="moveit_task_constructor_demo",
|
|
||||||
executable="ik_clearance_cost",
|
|
||||||
output="screen",
|
|
||||||
parameters=[
|
|
||||||
moveit_config.joint_limits,
|
|
||||||
moveit_config.robot_description,
|
|
||||||
moveit_config.robot_description_semantic,
|
|
||||||
moveit_config.robot_description_kinematics,
|
|
||||||
],
|
|
||||||
)
|
|
||||||
|
|
||||||
return LaunchDescription([cartesian_task])
|
|
||||||
@ -1,25 +0,0 @@
|
|||||||
from launch import LaunchDescription
|
|
||||||
from launch_ros.actions import Node
|
|
||||||
from moveit_configs_utils import MoveItConfigsBuilder
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
|
||||||
moveit_config = (
|
|
||||||
MoveItConfigsBuilder("moveit_resources_panda")
|
|
||||||
.robot_description(file_path="config/panda.urdf.xacro")
|
|
||||||
.to_moveit_configs()
|
|
||||||
)
|
|
||||||
|
|
||||||
modular_task = Node(
|
|
||||||
package="moveit_task_constructor_demo",
|
|
||||||
executable="modular",
|
|
||||||
output="screen",
|
|
||||||
parameters=[
|
|
||||||
moveit_config.joint_limits,
|
|
||||||
moveit_config.robot_description,
|
|
||||||
moveit_config.robot_description_semantic,
|
|
||||||
moveit_config.robot_description_kinematics,
|
|
||||||
],
|
|
||||||
)
|
|
||||||
|
|
||||||
return LaunchDescription([modular_task])
|
|
||||||
@ -1,36 +0,0 @@
|
|||||||
import os
|
|
||||||
|
|
||||||
from ament_index_python.packages import get_package_share_directory
|
|
||||||
from launch import LaunchDescription
|
|
||||||
from launch_ros.actions import Node
|
|
||||||
from moveit_configs_utils import MoveItConfigsBuilder
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
|
||||||
moveit_config = (
|
|
||||||
MoveItConfigsBuilder("moveit_resources_panda")
|
|
||||||
.planning_pipelines(pipelines=["ompl"])
|
|
||||||
.robot_description(file_path="config/panda.urdf.xacro")
|
|
||||||
.trajectory_execution(file_path="config/gripper_moveit_controllers.yaml")
|
|
||||||
.to_moveit_configs()
|
|
||||||
)
|
|
||||||
|
|
||||||
pick_place_demo = Node(
|
|
||||||
package="moveit_task_constructor_demo",
|
|
||||||
executable="pick_place_demo",
|
|
||||||
output="screen",
|
|
||||||
parameters=[
|
|
||||||
os.path.join(
|
|
||||||
get_package_share_directory("moveit_task_constructor_demo"),
|
|
||||||
"config",
|
|
||||||
"panda_config.yaml",
|
|
||||||
),
|
|
||||||
moveit_config.robot_description,
|
|
||||||
moveit_config.robot_description_semantic,
|
|
||||||
moveit_config.robot_description_kinematics,
|
|
||||||
moveit_config.planning_pipelines,
|
|
||||||
moveit_config.joint_limits,
|
|
||||||
],
|
|
||||||
)
|
|
||||||
|
|
||||||
return LaunchDescription([pick_place_demo])
|
|
||||||
@ -1,4 +1,6 @@
|
|||||||
from launch import LaunchDescription
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument
|
||||||
|
from launch.substitutions import LaunchConfiguration
|
||||||
from launch_ros.actions import Node
|
from launch_ros.actions import Node
|
||||||
from moveit_configs_utils import MoveItConfigsBuilder
|
from moveit_configs_utils import MoveItConfigsBuilder
|
||||||
|
|
||||||
@ -7,21 +9,21 @@ def generate_launch_description():
|
|||||||
moveit_config = (
|
moveit_config = (
|
||||||
MoveItConfigsBuilder("moveit_resources_panda")
|
MoveItConfigsBuilder("moveit_resources_panda")
|
||||||
.robot_description(file_path="config/panda.urdf.xacro")
|
.robot_description(file_path="config/panda.urdf.xacro")
|
||||||
.planning_pipelines(pipelines=["ompl"])
|
|
||||||
.to_moveit_configs()
|
.to_moveit_configs()
|
||||||
)
|
)
|
||||||
|
|
||||||
cartesian_task = Node(
|
node = Node(
|
||||||
package="moveit_task_constructor_demo",
|
package="moveit_task_constructor_demo",
|
||||||
executable="alternative_path_costs",
|
executable=LaunchConfiguration("exe"),
|
||||||
output="screen",
|
output="screen",
|
||||||
parameters=[
|
parameters=[
|
||||||
moveit_config.joint_limits,
|
|
||||||
moveit_config.robot_description,
|
moveit_config.robot_description,
|
||||||
moveit_config.robot_description_semantic,
|
moveit_config.robot_description_semantic,
|
||||||
moveit_config.robot_description_kinematics,
|
moveit_config.robot_description_kinematics,
|
||||||
|
moveit_config.joint_limits,
|
||||||
moveit_config.planning_pipelines,
|
moveit_config.planning_pipelines,
|
||||||
],
|
],
|
||||||
)
|
)
|
||||||
|
|
||||||
return LaunchDescription([cartesian_task])
|
arg = DeclareLaunchArgument(name="exe")
|
||||||
|
return LaunchDescription([arg, node])
|
||||||
Loading…
Reference in New Issue
Block a user