Add minimal pick-and-place case with world embedded
This commit is contained in:
parent
209e99a4b3
commit
a87fb8a7ec
64 changed files with 2419 additions and 275 deletions
|
@ -3,18 +3,15 @@ from launch import LaunchDescription
|
|||
from launch.actions import (
|
||||
DeclareLaunchArgument,
|
||||
IncludeLaunchDescription,
|
||||
RegisterEventHandler
|
||||
ExecuteProcess
|
||||
)
|
||||
from ament_index_python.packages import get_package_share_directory, get_package_share_path
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch.conditions import IfCondition, UnlessCondition
|
||||
from launch.event_handlers import OnProcessExit, OnExecutionComplete
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from ur_moveit_config.launch_common import load_yaml
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
declared_arguments = []
|
||||
# UR specific arguments
|
||||
|
@ -26,6 +23,13 @@ def generate_launch_description():
|
|||
default_value="ur5e",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"with_gripper",
|
||||
default_value="true",
|
||||
description="With gripper or not?",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"safety_limits",
|
||||
|
@ -63,6 +67,13 @@ def generate_launch_description():
|
|||
description="YAML file with the controllers configuration.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"controllers_with_gripper_file",
|
||||
default_value="ur_plus_gripper_controllers.yaml",
|
||||
description="YAML file with the UR + gripper_controller configuration.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"description_package",
|
||||
|
@ -101,6 +112,14 @@ def generate_launch_description():
|
|||
description="Robot controller to start.",
|
||||
)
|
||||
)
|
||||
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"initial_gripper_controller",
|
||||
default_value="gripper_controller",
|
||||
description="Robot controller to start.",
|
||||
)
|
||||
)
|
||||
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
|
@ -129,26 +148,31 @@ def generate_launch_description():
|
|||
DeclareLaunchArgument("launch_rviz", default_value="true", description="Launch RViz?")
|
||||
)
|
||||
|
||||
|
||||
|
||||
# Initialize Arguments
|
||||
# TODO тут всё переименовать и сделать боеле универсальным как под нашего робото так и под UR чтобы запускалось одинаково
|
||||
rbs_robot_type = LaunchConfiguration("rbs_robot_type")
|
||||
safety_limits = LaunchConfiguration("safety_limits")
|
||||
safety_pos_margin = LaunchConfiguration("safety_pos_margin")
|
||||
safety_k_position = LaunchConfiguration("safety_k_position")
|
||||
# General arguments
|
||||
runtime_config_package = LaunchConfiguration("runtime_config_package")
|
||||
controllers_file = LaunchConfiguration("controllers_file")
|
||||
with_gripper_condition = LaunchConfiguration("with_gripper")
|
||||
controllers_file = LaunchConfiguration("controllers_with_gripper_file")
|
||||
|
||||
description_package = LaunchConfiguration("description_package")
|
||||
description_file = LaunchConfiguration("description_file")
|
||||
prefix = LaunchConfiguration("prefix")
|
||||
start_joint_controller = LaunchConfiguration("start_joint_controller")
|
||||
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
|
||||
initial_gripper_controller = LaunchConfiguration("initial_gripper_controller")
|
||||
launch_rviz = LaunchConfiguration("launch_rviz")
|
||||
moveit_config_package = LaunchConfiguration("moveit_config_package")
|
||||
moveit_config_file = LaunchConfiguration("moveit_config_file")
|
||||
use_sim_time = LaunchConfiguration("use_sim_time")
|
||||
|
||||
initial_joint_controllers = PathJoinSubstitution(
|
||||
|
||||
initial_joint_controllers_file_path = PathJoinSubstitution(
|
||||
[FindPackageShare(runtime_config_package), "config", controllers_file]
|
||||
)
|
||||
|
||||
|
@ -157,7 +181,7 @@ def generate_launch_description():
|
|||
)
|
||||
|
||||
world_config_file = PathJoinSubstitution(
|
||||
[FindPackageShare("sdf_models"), "worlds", "empty_world.sdf"] # TODO тут пакет извне должен задаваться
|
||||
[FindPackageShare("rbs_simulation"), "worlds", "mir.sdf"]
|
||||
)
|
||||
|
||||
robot_description_content = Command(
|
||||
|
@ -180,7 +204,7 @@ def generate_launch_description():
|
|||
"name:=",
|
||||
"ur",
|
||||
" ",
|
||||
"ur_type:=", # TODO сделать более универсальным
|
||||
"ur_type:=",
|
||||
rbs_robot_type,
|
||||
" ",
|
||||
"prefix:=",
|
||||
|
@ -189,7 +213,10 @@ def generate_launch_description():
|
|||
"sim_ignition:=true",
|
||||
" ",
|
||||
"simulation_controllers:=",
|
||||
initial_joint_controllers,
|
||||
initial_joint_controllers_file_path,
|
||||
" ",
|
||||
"with_gripper:=",
|
||||
with_gripper_condition
|
||||
]
|
||||
)
|
||||
robot_description = {"robot_description": robot_description_content}
|
||||
|
@ -220,13 +247,20 @@ def generate_launch_description():
|
|||
arguments=[initial_joint_controller, "--controller-manager", "/controller_manager", "--stopped"],
|
||||
condition=UnlessCondition(start_joint_controller),
|
||||
)
|
||||
|
||||
gripper_controller = ExecuteProcess(
|
||||
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
|
||||
"gripper_controller"],
|
||||
output='screen',
|
||||
condition=IfCondition(with_gripper_condition)
|
||||
)
|
||||
|
||||
# Gazebo nodes
|
||||
gazebo = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
os.path.join(get_package_share_path('ros_ign_gazebo'), 'launch', 'ign_gazebo.launch.py')),
|
||||
launch_arguments={'ign_args': ['-r'," ", world_config_file]}.items(),
|
||||
)
|
||||
PythonLaunchDescriptionSource(
|
||||
[os.path.join(get_package_share_directory('ros_ign_gazebo'),
|
||||
'launch', 'ign_gazebo.launch.py')]),
|
||||
launch_arguments=[('ign_args', [' -r ',world_config_file, " --physics-engine ignition-physics-dartsim-plugin --render-engine ogre2"])])
|
||||
# Spawn robot
|
||||
gazebo_spawn_robot = Node(package='ros_ign_gazebo', executable='create',
|
||||
arguments=[
|
||||
|
@ -252,6 +286,8 @@ def generate_launch_description():
|
|||
"prefix:=",
|
||||
prefix,
|
||||
" ",
|
||||
"with_gripper:=",
|
||||
with_gripper_condition
|
||||
]
|
||||
)
|
||||
robot_description_semantic = {"robot_description_semantic": robot_description_semantic_content}
|
||||
|
@ -260,7 +296,6 @@ def generate_launch_description():
|
|||
[FindPackageShare(moveit_config_package), "config", "kinematics.yaml"]
|
||||
)
|
||||
|
||||
|
||||
# Planning Configuration
|
||||
ompl_planning_pipeline_config = {
|
||||
"move_group": {
|
||||
|
@ -269,16 +304,10 @@ def generate_launch_description():
|
|||
"start_state_max_bounds_error": 0.1,
|
||||
}
|
||||
}
|
||||
ompl_planning_yaml = load_yaml("ur_moveit_config", "config/ompl_planning.yaml") # TODO сделать извне
|
||||
ompl_planning_yaml = load_yaml("ur_moveit_config", "config/ompl_planning.yaml")
|
||||
ompl_planning_pipeline_config["move_group"].update(ompl_planning_yaml)
|
||||
|
||||
# Trajectory Execution Configuration
|
||||
controllers_yaml = load_yaml("ur_moveit_config", "config/controllers.yaml")
|
||||
# the scaled_joint_trajectory_controller does not work on fake hardware
|
||||
change_controllers = True
|
||||
if change_controllers == "true":
|
||||
controllers_yaml["scaled_joint_trajectory_controller"]["default"] = False
|
||||
controllers_yaml["joint_trajectory_controller"]["default"] = True
|
||||
|
||||
moveit_controllers = {
|
||||
"moveit_simple_controller_manager": controllers_yaml,
|
||||
|
@ -287,7 +316,7 @@ def generate_launch_description():
|
|||
|
||||
trajectory_execution = {
|
||||
"moveit_manage_controllers": True,
|
||||
"trajectory_execution.allowed_execution_duration_scaling": 1.2,
|
||||
"trajectory_execution.allowed_execution_duration_scaling": 100.0,
|
||||
"trajectory_execution.allowed_goal_duration_margin": 0.5,
|
||||
"trajectory_execution.allowed_start_tolerance": 0.01,
|
||||
}
|
||||
|
@ -299,12 +328,10 @@ def generate_launch_description():
|
|||
"publish_transforms_updates": True,
|
||||
}
|
||||
|
||||
# Start the actual move_group node/action server
|
||||
move_group_node = Node(
|
||||
package="moveit_ros_move_group",
|
||||
executable="move_group",
|
||||
output="screen",
|
||||
name="move_group",
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
|
@ -326,24 +353,40 @@ def generate_launch_description():
|
|||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
ompl_planning_pipeline_config,
|
||||
robot_description_kinematics,
|
||||
],
|
||||
condition=IfCondition(launch_rviz),
|
||||
)
|
||||
# TODO: Launch skill servers in other launch file
|
||||
move_topose_action_server = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_topose_action_server",
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
{"use_sim_time": use_sim_time},
|
||||
]
|
||||
)
|
||||
|
||||
gripper_control_node = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="gripper_control_action_server",
|
||||
parameters= [
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
{"use_sim_time": use_sim_time},
|
||||
]
|
||||
)
|
||||
|
||||
move_topose_action_server = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_topose_action_server",
|
||||
name="move_to_pose_moveit",
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
ompl_planning_pipeline_config,
|
||||
trajectory_execution,
|
||||
moveit_controllers,
|
||||
planning_scene_monitor_parameters,
|
||||
{"use_sim_time": use_sim_time},
|
||||
]
|
||||
)
|
||||
|
@ -351,19 +394,49 @@ def generate_launch_description():
|
|||
move_cartesian_path_action_server = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_cartesian_path_action_server",
|
||||
name="move_cartesian_path_action_server",
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
ompl_planning_pipeline_config,
|
||||
trajectory_execution,
|
||||
moveit_controllers,
|
||||
planning_scene_monitor_parameters,
|
||||
{"use_sim_time": use_sim_time},
|
||||
]
|
||||
)
|
||||
|
||||
|
||||
move_joint_state_action_server = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_to_joint_states_action_server",
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
{"use_sim_time": use_sim_time},
|
||||
]
|
||||
)
|
||||
|
||||
points_params = load_yaml("rbs_bt_executor", "config/gripperPositions.yaml")
|
||||
|
||||
grasp_pose_loader = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="pick_place_pose_loader",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
points_params
|
||||
]
|
||||
)
|
||||
|
||||
# add_planning_scene_object = Node(
|
||||
# package="rbs_skill_servers",
|
||||
# executable="add_planning_scene_object_service",
|
||||
# output="screen",
|
||||
# parameters=[
|
||||
# robot_description,
|
||||
# robot_description_semantic,
|
||||
# robot_description_kinematics,
|
||||
# {"use_sim_time": use_sim_time},
|
||||
# ]
|
||||
# )
|
||||
|
||||
nodes_to_start = [
|
||||
robot_state_publisher_node,
|
||||
joint_state_broadcaster_spawner,
|
||||
|
@ -373,8 +446,13 @@ def generate_launch_description():
|
|||
gazebo,
|
||||
gazebo_spawn_robot,
|
||||
move_group_node,
|
||||
gripper_controller,
|
||||
gripper_control_node,
|
||||
move_topose_action_server,
|
||||
move_cartesian_path_action_server,
|
||||
move_joint_state_action_server,
|
||||
grasp_pose_loader,
|
||||
#add_planning_scene_object
|
||||
]
|
||||
|
||||
return LaunchDescription(declared_arguments + nodes_to_start)
|
Loading…
Add table
Add a link
Reference in a new issue